2 ******************************************************************************
3 * @file stm32f7xx_hal_spdifrx.c
4 * @author MCD Application Team
7 * @brief This file provides firmware functions to manage the following
8 * functionalities of the SPDIFRX audio interface:
9 * + Initialization and Configuration
10 * + Data transfers functions
11 * + DMA transfers management
12 * + Interrupts and flags management
14 ===============================================================================
15 ##### How to use this driver #####
16 ===============================================================================
18 The SPDIFRX HAL driver can be used as follow:
20 (#) Declare SPDIFRX_HandleTypeDef handle structure.
21 (#) Initialize the SPDIFRX low level resources by implement the HAL_SPDIFRX_MspInit() API:
22 (##) Enable the SPDIFRX interface clock.
23 (##) SPDIFRX pins configuration:
24 (+++) Enable the clock for the SPDIFRX GPIOs.
25 (+++) Configure these SPDIFRX pins as alternate function pull-up.
26 (##) NVIC configuration if you need to use interrupt process (HAL_SPDIFRX_ReceiveControlFlow_IT() and HAL_SPDIFRX_ReceiveDataFlow_IT() API's).
27 (+++) Configure the SPDIFRX interrupt priority.
28 (+++) Enable the NVIC SPDIFRX IRQ handle.
29 (##) DMA Configuration if you need to use DMA process (HAL_SPDIFRX_ReceiveDataFlow_DMA() and HAL_SPDIFRX_ReceiveControlFlow_DMA() API's).
30 (+++) Declare a DMA handle structure for the reception of the Data Flow channel.
31 (+++) Declare a DMA handle structure for the reception of the Control Flow channel.
32 (+++) Enable the DMAx interface clock.
33 (+++) Configure the declared DMA handle structure CtrlRx/DataRx with the required parameters.
34 (+++) Configure the DMA Channel.
35 (+++) Associate the initialized DMA handle to the SPDIFRX DMA CtrlRx/DataRx handle.
36 (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on the
37 DMA CtrlRx/DataRx channel.
39 (#) Program the input selection, re-tries number, wait for activity, channel status selection, data format, stereo mode and masking of user bits
40 using HAL_SPDIFRX_Init() function.
42 -@- The specific SPDIFRX interrupts (RXNE/CSRNE and Error Interrupts) will be managed using the macros
43 __SPDIFRX_ENABLE_IT() and __SPDIFRX_DISABLE_IT() inside the receive process.
44 -@- Make sure that ck_spdif clock is configured.
46 (#) Three operation modes are available within this driver :
48 *** Polling mode for reception operation (for debug purpose) ***
49 ================================================================
51 (+) Receive data flow in blocking mode using HAL_SPDIFRX_ReceiveDataFlow()
52 (+) Receive control flow of data in blocking mode using HAL_SPDIFRX_ReceiveControlFlow()
54 *** Interrupt mode for reception operation ***
55 =========================================
57 (+) Receive an amount of data (Data Flow) in non blocking mode using HAL_SPDIFRX_ReceiveDataFlow_IT()
58 (+) Receive an amount of data (Control Flow) in non blocking mode using HAL_SPDIFRX_ReceiveControlFlow_IT()
59 (+) At reception end of half transfer HAL_SPDIFRX_RxHalfCpltCallback is executed and user can
60 add his own code by customization of function pointer HAL_SPDIFRX_RxHalfCpltCallback
61 (+) At reception end of transfer HAL_SPDIFRX_RxCpltCallback is executed and user can
62 add his own code by customization of function pointer HAL_SPDIFRX_RxCpltCallback
63 (+) In case of transfer Error, HAL_SPDIFRX_ErrorCallback() function is executed and user can
64 add his own code by customization of function pointer HAL_SPDIFRX_ErrorCallback
66 *** DMA mode for reception operation ***
67 ========================================
69 (+) Receive an amount of data (Data Flow) in non blocking mode (DMA) using HAL_SPDIFRX_ReceiveDataFlow_DMA()
70 (+) Receive an amount of data (Control Flow) in non blocking mode (DMA) using HAL_SPDIFRX_ReceiveControlFlow_DMA()
71 (+) At reception end of half transfer HAL_SPDIFRX_RxHalfCpltCallback is executed and user can
72 add his own code by customization of function pointer HAL_SPDIFRX_RxHalfCpltCallback
73 (+) At reception end of transfer HAL_SPDIFRX_RxCpltCallback is executed and user can
74 add his own code by customization of function pointer HAL_SPDIFRX_RxCpltCallback
75 (+) In case of transfer Error, HAL_SPDIFRX_ErrorCallback() function is executed and user can
76 add his own code by customization of function pointer HAL_SPDIFRX_ErrorCallback
77 (+) Stop the DMA Transfer using HAL_SPDIFRX_DMAStop()
79 *** SPDIFRX HAL driver macros list ***
80 =============================================
82 Below the list of most used macros in USART HAL driver.
83 (+) __HAL_SPDIFRX_IDLE: Disable the specified SPDIFRX peripheral (IDEL State)
84 (+) __HAL_SPDIFRX_SYNC: Enable the synchronization state of the specified SPDIFRX peripheral (SYNC State)
85 (+) __HAL_SPDIFRX_RCV: Enable the receive state of the specified SPDIFRX peripheral (RCV State)
86 (+) __HAL_SPDIFRX_ENABLE_IT : Enable the specified SPDIFRX interrupts
87 (+) __HAL_SPDIFRX_DISABLE_IT : Disable the specified SPDIFRX interrupts
88 (+) __HAL_SPDIFRX_GET_FLAG: Check whether the specified SPDIFRX flag is set or not.
91 (@) You can refer to the SPDIFRX HAL driver header file for more useful macros
94 ******************************************************************************
97 * <h2><center>© COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
99 * Redistribution and use in source and binary forms, with or without modification,
100 * are permitted provided that the following conditions are met:
101 * 1. Redistributions of source code must retain the above copyright notice,
102 * this list of conditions and the following disclaimer.
103 * 2. Redistributions in binary form must reproduce the above copyright notice,
104 * this list of conditions and the following disclaimer in the documentation
105 * and/or other materials provided with the distribution.
106 * 3. Neither the name of STMicroelectronics nor the names of its contributors
107 * may be used to endorse or promote products derived from this software
108 * without specific prior written permission.
110 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
111 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
112 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
113 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
114 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
115 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
116 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
117 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
118 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
119 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
121 ******************************************************************************
124 /* Includes ------------------------------------------------------------------*/
125 #include "stm32f7xx_hal.h"
127 /** @addtogroup STM32F7xx_HAL_Driver
130 /** @defgroup SPDIFRX SPDIFRX
131 * @brief SPDIFRX HAL module driver
135 #ifdef HAL_SPDIFRX_MODULE_ENABLED
136 #if defined (SPDIFRX)
138 /* Private typedef -----------------------------------------------------------*/
139 /* Private define ------------------------------------------------------------*/
140 #define SPDIFRX_TIMEOUT_VALUE 0xFFFF
142 /* Private macro -------------------------------------------------------------*/
143 /* Private variables ---------------------------------------------------------*/
144 /* Private function prototypes -----------------------------------------------*/
145 /** @addtogroup SPDIFRX_Private_Functions
148 static void SPDIFRX_DMARxCplt(DMA_HandleTypeDef
*hdma
);
149 static void SPDIFRX_DMARxHalfCplt(DMA_HandleTypeDef
*hdma
);
150 static void SPDIFRX_DMACxCplt(DMA_HandleTypeDef
*hdma
);
151 static void SPDIFRX_DMACxHalfCplt(DMA_HandleTypeDef
*hdma
);
152 static void SPDIFRX_DMAError(DMA_HandleTypeDef
*hdma
);
153 static void SPDIFRX_ReceiveControlFlow_IT(SPDIFRX_HandleTypeDef
*hspdif
);
154 static void SPDIFRX_ReceiveDataFlow_IT(SPDIFRX_HandleTypeDef
*hspdif
);
155 static HAL_StatusTypeDef
SPDIFRX_WaitOnFlagUntilTimeout(SPDIFRX_HandleTypeDef
*hspdif
, uint32_t Flag
, FlagStatus Status
, uint32_t Timeout
, uint32_t tickstart
);
159 /* Exported functions ---------------------------------------------------------*/
161 /** @defgroup SPDIFRX_Exported_Functions SPDIFRX Exported Functions
165 /** @defgroup SPDIFRX_Exported_Functions_Group1 Initialization and de-initialization functions
166 * @brief Initialization and Configuration functions
169 ===============================================================================
170 ##### Initialization and de-initialization functions #####
171 ===============================================================================
172 [..] This subsection provides a set of functions allowing to initialize and
173 de-initialize the SPDIFRX peripheral:
175 (+) User must Implement HAL_SPDIFRX_MspInit() function in which he configures
176 all related peripherals resources (CLOCK, GPIO, DMA, IT and NVIC ).
178 (+) Call the function HAL_SPDIFRX_Init() to configure the SPDIFRX peripheral with
179 the selected configuration:
180 (++) Input Selection (IN0, IN1,...)
181 (++) Maximum allowed re-tries during synchronization phase
182 (++) Wait for activity on SPDIF selected input
183 (++) Channel status selection (from channel A or B)
184 (++) Data format (LSB, MSB, ...)
186 (++) User bits masking (PT,C,U,V,...)
188 (+) Call the function HAL_SPDIFRX_DeInit() to restore the default configuration
189 of the selected SPDIFRXx peripheral.
195 * @brief Initializes the SPDIFRX according to the specified parameters
196 * in the SPDIFRX_InitTypeDef and create the associated handle.
197 * @param hspdif: SPDIFRX handle
200 HAL_StatusTypeDef
HAL_SPDIFRX_Init(SPDIFRX_HandleTypeDef
*hspdif
)
204 /* Check the SPDIFRX handle allocation */
210 /* Check the SPDIFRX parameters */
211 assert_param(IS_STEREO_MODE(hspdif
->Init
.StereoMode
));
212 assert_param(IS_SPDIFRX_INPUT_SELECT(hspdif
->Init
.InputSelection
));
213 assert_param(IS_SPDIFRX_MAX_RETRIES(hspdif
->Init
.Retries
));
214 assert_param(IS_SPDIFRX_WAIT_FOR_ACTIVITY(hspdif
->Init
.WaitForActivity
));
215 assert_param(IS_SPDIFRX_CHANNEL(hspdif
->Init
.ChannelSelection
));
216 assert_param(IS_SPDIFRX_DATA_FORMAT(hspdif
->Init
.DataFormat
));
217 assert_param(IS_PREAMBLE_TYPE_MASK(hspdif
->Init
.PreambleTypeMask
));
218 assert_param(IS_CHANNEL_STATUS_MASK(hspdif
->Init
.ChannelStatusMask
));
219 assert_param(IS_VALIDITY_MASK(hspdif
->Init
.ValidityBitMask
));
220 assert_param(IS_PARITY_ERROR_MASK(hspdif
->Init
.ParityErrorMask
));
222 if(hspdif
->State
== HAL_SPDIFRX_STATE_RESET
)
224 /* Allocate lock resource and initialize it */
225 hspdif
->Lock
= HAL_UNLOCKED
;
226 /* Init the low level hardware : GPIO, CLOCK, CORTEX...etc */
227 HAL_SPDIFRX_MspInit(hspdif
);
230 /* SPDIFRX peripheral state is BUSY*/
231 hspdif
->State
= HAL_SPDIFRX_STATE_BUSY
;
233 /* Disable SPDIFRX interface (IDLE State) */
234 __HAL_SPDIFRX_IDLE(hspdif
);
236 /* Reset the old SPDIFRX CR configuration */
237 tmpreg
= hspdif
->Instance
->CR
;
239 tmpreg
&= ~((uint16_t) SPDIFRX_CR_RXSTEO
| SPDIFRX_CR_DRFMT
| SPDIFRX_CR_PMSK
|
240 SPDIFRX_CR_VMSK
| SPDIFRX_CR_CUMSK
| SPDIFRX_CR_PTMSK
|
241 SPDIFRX_CR_CHSEL
| SPDIFRX_CR_NBTR
| SPDIFRX_CR_WFA
| SPDIFRX_CR_INSEL
);
243 /* Sets the new configuration of the SPDIFRX peripheral */
244 tmpreg
|= ((uint16_t) hspdif
->Init
.StereoMode
|
245 hspdif
->Init
.InputSelection
|
246 hspdif
->Init
.Retries
|
247 hspdif
->Init
.WaitForActivity
|
248 hspdif
->Init
.ChannelSelection
|
249 hspdif
->Init
.DataFormat
|
250 hspdif
->Init
.PreambleTypeMask
|
251 hspdif
->Init
.ChannelStatusMask
|
252 hspdif
->Init
.ValidityBitMask
|
253 hspdif
->Init
.ParityErrorMask
);
255 hspdif
->Instance
->CR
= tmpreg
;
257 hspdif
->ErrorCode
= HAL_SPDIFRX_ERROR_NONE
;
259 /* SPDIFRX peripheral state is READY*/
260 hspdif
->State
= HAL_SPDIFRX_STATE_READY
;
266 * @brief DeInitializes the SPDIFRX peripheral
267 * @param hspdif: SPDIFRX handle
270 HAL_StatusTypeDef
HAL_SPDIFRX_DeInit(SPDIFRX_HandleTypeDef
*hspdif
)
272 /* Check the SPDIFRX handle allocation */
278 /* Check the parameters */
279 assert_param(IS_SPDIFRX_ALL_INSTANCE(hspdif
->Instance
));
281 hspdif
->State
= HAL_SPDIFRX_STATE_BUSY
;
283 /* Disable SPDIFRX interface (IDLE state) */
284 __HAL_SPDIFRX_IDLE(hspdif
);
286 /* DeInit the low level hardware: GPIO, CLOCK, NVIC... */
287 HAL_SPDIFRX_MspDeInit(hspdif
);
289 hspdif
->ErrorCode
= HAL_SPDIFRX_ERROR_NONE
;
291 /* SPDIFRX peripheral state is RESET*/
292 hspdif
->State
= HAL_SPDIFRX_STATE_RESET
;
295 __HAL_UNLOCK(hspdif
);
301 * @brief SPDIFRX MSP Init
302 * @param hspdif: SPDIFRX handle
305 __weak
void HAL_SPDIFRX_MspInit(SPDIFRX_HandleTypeDef
*hspdif
)
307 /* Prevent unused argument(s) compilation warning */
310 /* NOTE : This function Should not be modified, when the callback is needed,
311 the HAL_SPDIFRX_MspInit could be implemented in the user file
316 * @brief SPDIFRX MSP DeInit
317 * @param hspdif: SPDIFRX handle
320 __weak
void HAL_SPDIFRX_MspDeInit(SPDIFRX_HandleTypeDef
*hspdif
)
322 /* Prevent unused argument(s) compilation warning */
325 /* NOTE : This function Should not be modified, when the callback is needed,
326 the HAL_SPDIFRX_MspDeInit could be implemented in the user file
331 * @brief Sets the SPDIFRX dtat format according to the specified parameters
332 * in the SPDIFRX_InitTypeDef.
333 * @param hspdif: SPDIFRX handle
334 * @param sDataFormat: SPDIFRX data format
337 HAL_StatusTypeDef
HAL_SPDIFRX_SetDataFormat(SPDIFRX_HandleTypeDef
*hspdif
, SPDIFRX_SetDataFormatTypeDef sDataFormat
)
341 /* Check the SPDIFRX handle allocation */
347 /* Check the SPDIFRX parameters */
348 assert_param(IS_STEREO_MODE(sDataFormat
.StereoMode
));
349 assert_param(IS_SPDIFRX_DATA_FORMAT(sDataFormat
.DataFormat
));
350 assert_param(IS_PREAMBLE_TYPE_MASK(sDataFormat
.PreambleTypeMask
));
351 assert_param(IS_CHANNEL_STATUS_MASK(sDataFormat
.ChannelStatusMask
));
352 assert_param(IS_VALIDITY_MASK(sDataFormat
.ValidityBitMask
));
353 assert_param(IS_PARITY_ERROR_MASK(sDataFormat
.ParityErrorMask
));
355 /* Reset the old SPDIFRX CR configuration */
356 tmpreg
= hspdif
->Instance
->CR
;
358 if(((tmpreg
& SPDIFRX_STATE_RCV
) == SPDIFRX_STATE_RCV
) &&
359 (((tmpreg
& SPDIFRX_CR_DRFMT
) != sDataFormat
.DataFormat
) ||
360 ((tmpreg
& SPDIFRX_CR_RXSTEO
) != sDataFormat
.StereoMode
)))
365 tmpreg
&= ~((uint16_t) SPDIFRX_CR_RXSTEO
| SPDIFRX_CR_DRFMT
| SPDIFRX_CR_PMSK
|
366 SPDIFRX_CR_VMSK
| SPDIFRX_CR_CUMSK
| SPDIFRX_CR_PTMSK
);
368 /* Sets the new configuration of the SPDIFRX peripheral */
369 tmpreg
|= ((uint16_t) sDataFormat
.StereoMode
|
370 sDataFormat
.DataFormat
|
371 sDataFormat
.PreambleTypeMask
|
372 sDataFormat
.ChannelStatusMask
|
373 sDataFormat
.ValidityBitMask
|
374 sDataFormat
.ParityErrorMask
);
376 hspdif
->Instance
->CR
= tmpreg
;
385 /** @defgroup SPDIFRX_Exported_Functions_Group2 IO operation functions
386 * @brief Data transfers functions
389 ===============================================================================
390 ##### IO operation functions #####
391 ===============================================================================
393 This subsection provides a set of functions allowing to manage the SPDIFRX data
396 (#) There is two mode of transfer:
397 (++) Blocking mode : The communication is performed in the polling mode.
398 The status of all data processing is returned by the same function
399 after finishing transfer.
400 (++) No-Blocking mode : The communication is performed using Interrupts
401 or DMA. These functions return the status of the transfer start-up.
402 The end of the data processing will be indicated through the
403 dedicated SPDIFRX IRQ when using Interrupt mode or the DMA IRQ when
406 (#) Blocking mode functions are :
407 (++) HAL_SPDIFRX_ReceiveDataFlow()
408 (++) HAL_SPDIFRX_ReceiveControlFlow()
409 (+@) Do not use blocking mode to receive both control and data flow at the same time.
411 (#) No-Blocking mode functions with Interrupt are :
412 (++) HAL_SPDIFRX_ReceiveControlFlow_IT()
413 (++) HAL_SPDIFRX_ReceiveDataFlow_IT()
415 (#) No-Blocking mode functions with DMA are :
416 (++) HAL_SPDIFRX_ReceiveControlFlow_DMA()
417 (++) HAL_SPDIFRX_ReceiveDataFlow_DMA()
419 (#) A set of Transfer Complete Callbacks are provided in No_Blocking mode:
420 (++) HAL_SPDIFRX_RxCpltCallback()
421 (++) HAL_SPDIFRX_ErrorCallback()
429 * @brief Receives an amount of data (Data Flow) in blocking mode.
430 * @param hspdif: pointer to SPDIFRX_HandleTypeDef structure that contains
431 * the configuration information for SPDIFRX module.
432 * @param pData: Pointer to data buffer
433 * @param Size: Amount of data to be received
434 * @param Timeout: Timeout duration
437 HAL_StatusTypeDef
HAL_SPDIFRX_ReceiveDataFlow(SPDIFRX_HandleTypeDef
*hspdif
, uint32_t *pData
, uint16_t Size
, uint32_t Timeout
)
439 uint32_t tickstart
= 0U;
441 if((pData
== NULL
) || (Size
== 0U))
446 if(hspdif
->State
== HAL_SPDIFRX_STATE_READY
)
451 hspdif
->State
= HAL_SPDIFRX_STATE_BUSY
;
453 /* Start synchronisation */
454 __HAL_SPDIFRX_SYNC(hspdif
);
457 tickstart
= HAL_GetTick();
459 /* Wait until SYNCD flag is set */
460 if(SPDIFRX_WaitOnFlagUntilTimeout(hspdif
, SPDIFRX_FLAG_SYNCD
, RESET
, Timeout
, tickstart
) != HAL_OK
)
465 /* Start reception */
466 __HAL_SPDIFRX_RCV(hspdif
);
468 /* Receive data flow */
472 tickstart
= HAL_GetTick();
474 /* Wait until RXNE flag is set */
475 if(SPDIFRX_WaitOnFlagUntilTimeout(hspdif
, SPDIFRX_FLAG_RXNE
, RESET
, Timeout
, tickstart
) != HAL_OK
)
480 (*pData
++) = hspdif
->Instance
->DR
;
485 hspdif
->State
= HAL_SPDIFRX_STATE_READY
;
487 /* Process Unlocked */
488 __HAL_UNLOCK(hspdif
);
499 * @brief Receives an amount of data (Control Flow) in blocking mode.
500 * @param hspdif: pointer to a SPDIFRX_HandleTypeDef structure that contains
501 * the configuration information for SPDIFRX module.
502 * @param pData: Pointer to data buffer
503 * @param Size: Amount of data to be received
504 * @param Timeout: Timeout duration
507 HAL_StatusTypeDef
HAL_SPDIFRX_ReceiveControlFlow(SPDIFRX_HandleTypeDef
*hspdif
, uint32_t *pData
, uint16_t Size
, uint32_t Timeout
)
509 uint32_t tickstart
= 0U;
511 if((pData
== NULL
) || (Size
== 0U))
516 if(hspdif
->State
== HAL_SPDIFRX_STATE_READY
)
521 hspdif
->State
= HAL_SPDIFRX_STATE_BUSY
;
523 /* Start synchronization */
524 __HAL_SPDIFRX_SYNC(hspdif
);
527 tickstart
= HAL_GetTick();
529 /* Wait until SYNCD flag is set */
530 if(SPDIFRX_WaitOnFlagUntilTimeout(hspdif
, SPDIFRX_FLAG_SYNCD
, RESET
, Timeout
, tickstart
) != HAL_OK
)
535 /* Start reception */
536 __HAL_SPDIFRX_RCV(hspdif
);
538 /* Receive control flow */
542 tickstart
= HAL_GetTick();
544 /* Wait until CSRNE flag is set */
545 if(SPDIFRX_WaitOnFlagUntilTimeout(hspdif
, SPDIFRX_FLAG_CSRNE
, RESET
, Timeout
, tickstart
) != HAL_OK
)
550 (*pData
++) = hspdif
->Instance
->CSR
;
555 hspdif
->State
= HAL_SPDIFRX_STATE_READY
;
557 /* Process Unlocked */
558 __HAL_UNLOCK(hspdif
);
569 * @brief Receive an amount of data (Data Flow) in non-blocking mode with Interrupt
570 * @param hspdif: SPDIFRX handle
571 * @param pData: a 32-bit pointer to the Receive data buffer.
572 * @param Size: number of data sample to be received .
575 HAL_StatusTypeDef
HAL_SPDIFRX_ReceiveDataFlow_IT(SPDIFRX_HandleTypeDef
*hspdif
, uint32_t *pData
, uint16_t Size
)
577 uint32_t tickstart
= 0U;
579 if((hspdif
->State
== HAL_SPDIFRX_STATE_READY
) || (hspdif
->State
== HAL_SPDIFRX_STATE_BUSY_CX
))
581 if((pData
== NULL
) || (Size
== 0U))
589 hspdif
->pRxBuffPtr
= pData
;
590 hspdif
->RxXferSize
= Size
;
591 hspdif
->RxXferCount
= Size
;
593 hspdif
->ErrorCode
= HAL_SPDIFRX_ERROR_NONE
;
595 /* Check if a receive process is ongoing or not */
596 hspdif
->State
= HAL_SPDIFRX_STATE_BUSY_RX
;
599 /* Enable the SPDIFRX PE Error Interrupt */
600 __HAL_SPDIFRX_ENABLE_IT(hspdif
, SPDIFRX_IT_PERRIE
);
602 /* Enable the SPDIFRX OVR Error Interrupt */
603 __HAL_SPDIFRX_ENABLE_IT(hspdif
, SPDIFRX_IT_OVRIE
);
605 /* Process Unlocked */
606 __HAL_UNLOCK(hspdif
);
608 /* Enable the SPDIFRX RXNE interrupt */
609 __HAL_SPDIFRX_ENABLE_IT(hspdif
, SPDIFRX_IT_RXNE
);
611 if (((SPDIFRX
->CR
& SPDIFRX_CR_SPDIFEN
) != SPDIFRX_STATE_SYNC
) || ((SPDIFRX
->CR
& SPDIFRX_CR_SPDIFEN
) != 0x00U
))
613 /* Start synchronization */
614 __HAL_SPDIFRX_SYNC(hspdif
);
617 tickstart
= HAL_GetTick();
619 /* Wait until SYNCD flag is set */
620 if(SPDIFRX_WaitOnFlagUntilTimeout(hspdif
, SPDIFRX_FLAG_SYNCD
, RESET
, SPDIFRX_TIMEOUT_VALUE
, tickstart
) != HAL_OK
)
625 /* Start reception */
626 __HAL_SPDIFRX_RCV(hspdif
);
638 * @brief Receive an amount of data (Control Flow) with Interrupt
639 * @param hspdif: SPDIFRX handle
640 * @param pData: a 32-bit pointer to the Receive data buffer.
641 * @param Size: number of data sample (Control Flow) to be received :
644 HAL_StatusTypeDef
HAL_SPDIFRX_ReceiveControlFlow_IT(SPDIFRX_HandleTypeDef
*hspdif
, uint32_t *pData
, uint16_t Size
)
646 uint32_t tickstart
= 0U;
648 if((hspdif
->State
== HAL_SPDIFRX_STATE_READY
) || (hspdif
->State
== HAL_SPDIFRX_STATE_BUSY_RX
))
650 if((pData
== NULL
) || (Size
== 0U))
658 hspdif
->pCsBuffPtr
= pData
;
659 hspdif
->CsXferSize
= Size
;
660 hspdif
->CsXferCount
= Size
;
662 hspdif
->ErrorCode
= HAL_SPDIFRX_ERROR_NONE
;
664 /* Check if a receive process is ongoing or not */
665 hspdif
->State
= HAL_SPDIFRX_STATE_BUSY_CX
;
668 /* Enable the SPDIFRX PE Error Interrupt */
669 __HAL_SPDIFRX_ENABLE_IT(hspdif
, SPDIFRX_IT_PERRIE
);
671 /* Enable the SPDIFRX OVR Error Interrupt */
672 __HAL_SPDIFRX_ENABLE_IT(hspdif
, SPDIFRX_IT_OVRIE
);
674 /* Process Unlocked */
675 __HAL_UNLOCK(hspdif
);
677 /* Enable the SPDIFRX CSRNE interrupt */
678 __HAL_SPDIFRX_ENABLE_IT(hspdif
, SPDIFRX_IT_CSRNE
);
680 if (((SPDIFRX
->CR
& SPDIFRX_CR_SPDIFEN
) != SPDIFRX_STATE_SYNC
) || ((SPDIFRX
->CR
& SPDIFRX_CR_SPDIFEN
) != 0x00U
))
682 /* Start synchronization */
683 __HAL_SPDIFRX_SYNC(hspdif
);
686 tickstart
= HAL_GetTick();
688 /* Wait until SYNCD flag is set */
689 if(SPDIFRX_WaitOnFlagUntilTimeout(hspdif
, SPDIFRX_FLAG_SYNCD
, RESET
, SPDIFRX_TIMEOUT_VALUE
, tickstart
) != HAL_OK
)
694 /* Start reception */
695 __HAL_SPDIFRX_RCV(hspdif
);
707 * @brief Receive an amount of data (Data Flow) mode with DMA
708 * @param hspdif: SPDIFRX handle
709 * @param pData: a 32-bit pointer to the Receive data buffer.
710 * @param Size: number of data sample to be received :
713 HAL_StatusTypeDef
HAL_SPDIFRX_ReceiveDataFlow_DMA(SPDIFRX_HandleTypeDef
*hspdif
, uint32_t *pData
, uint16_t Size
)
715 uint32_t tickstart
= 0U;
717 if((pData
== NULL
) || (Size
== 0U))
722 if((hspdif
->State
== HAL_SPDIFRX_STATE_READY
) || (hspdif
->State
== HAL_SPDIFRX_STATE_BUSY_CX
))
724 hspdif
->pRxBuffPtr
= pData
;
725 hspdif
->RxXferSize
= Size
;
726 hspdif
->RxXferCount
= Size
;
731 hspdif
->ErrorCode
= HAL_SPDIFRX_ERROR_NONE
;
732 hspdif
->State
= HAL_SPDIFRX_STATE_BUSY_RX
;
734 /* Set the SPDIFRX Rx DMA Half transfer complete callback */
735 hspdif
->hdmaDrRx
->XferHalfCpltCallback
= SPDIFRX_DMARxHalfCplt
;
737 /* Set the SPDIFRX Rx DMA transfer complete callback */
738 hspdif
->hdmaDrRx
->XferCpltCallback
= SPDIFRX_DMARxCplt
;
740 /* Set the DMA error callback */
741 hspdif
->hdmaDrRx
->XferErrorCallback
= SPDIFRX_DMAError
;
743 /* Enable the DMA request */
744 HAL_DMA_Start_IT(hspdif
->hdmaDrRx
, (uint32_t)&hspdif
->Instance
->DR
, (uint32_t)hspdif
->pRxBuffPtr
, Size
);
746 /* Enable RXDMAEN bit in SPDIFRX CR register for data flow reception*/
747 hspdif
->Instance
->CR
|= SPDIFRX_CR_RXDMAEN
;
749 if (((SPDIFRX
->CR
& SPDIFRX_CR_SPDIFEN
) != SPDIFRX_STATE_SYNC
) || ((SPDIFRX
->CR
& SPDIFRX_CR_SPDIFEN
) != 0x00U
))
751 /* Start synchronization */
752 __HAL_SPDIFRX_SYNC(hspdif
);
755 tickstart
= HAL_GetTick();
757 /* Wait until SYNCD flag is set */
758 if(SPDIFRX_WaitOnFlagUntilTimeout(hspdif
, SPDIFRX_FLAG_SYNCD
, RESET
, SPDIFRX_TIMEOUT_VALUE
, tickstart
) != HAL_OK
)
763 /* Start reception */
764 __HAL_SPDIFRX_RCV(hspdif
);
767 /* Process Unlocked */
768 __HAL_UNLOCK(hspdif
);
779 * @brief Receive an amount of data (Control Flow) with DMA
780 * @param hspdif: SPDIFRX handle
781 * @param pData: a 32-bit pointer to the Receive data buffer.
782 * @param Size: number of data (Control Flow) sample to be received :
785 HAL_StatusTypeDef
HAL_SPDIFRX_ReceiveControlFlow_DMA(SPDIFRX_HandleTypeDef
*hspdif
, uint32_t *pData
, uint16_t Size
)
787 uint32_t tickstart
= 0U;
789 if((pData
== NULL
) || (Size
== 0U))
794 if((hspdif
->State
== HAL_SPDIFRX_STATE_READY
) || (hspdif
->State
== HAL_SPDIFRX_STATE_BUSY_RX
))
796 hspdif
->pCsBuffPtr
= pData
;
797 hspdif
->CsXferSize
= Size
;
798 hspdif
->CsXferCount
= Size
;
803 hspdif
->ErrorCode
= HAL_SPDIFRX_ERROR_NONE
;
804 hspdif
->State
= HAL_SPDIFRX_STATE_BUSY_CX
;
806 /* Set the SPDIFRX Rx DMA Half transfer complete callback */
807 hspdif
->hdmaCsRx
->XferHalfCpltCallback
= SPDIFRX_DMACxHalfCplt
;
809 /* Set the SPDIFRX Rx DMA transfer complete callback */
810 hspdif
->hdmaCsRx
->XferCpltCallback
= SPDIFRX_DMACxCplt
;
812 /* Set the DMA error callback */
813 hspdif
->hdmaCsRx
->XferErrorCallback
= SPDIFRX_DMAError
;
815 /* Enable the DMA request */
816 HAL_DMA_Start_IT(hspdif
->hdmaCsRx
, (uint32_t)&hspdif
->Instance
->CSR
, (uint32_t)hspdif
->pCsBuffPtr
, Size
);
818 /* Enable CBDMAEN bit in SPDIFRX CR register for control flow reception*/
819 hspdif
->Instance
->CR
|= SPDIFRX_CR_CBDMAEN
;
821 if (((SPDIFRX
->CR
& SPDIFRX_CR_SPDIFEN
) != SPDIFRX_STATE_SYNC
) || ((SPDIFRX
->CR
& SPDIFRX_CR_SPDIFEN
) != 0x00U
))
823 /* Start synchronization */
824 __HAL_SPDIFRX_SYNC(hspdif
);
827 tickstart
= HAL_GetTick();
829 /* Wait until SYNCD flag is set */
830 if(SPDIFRX_WaitOnFlagUntilTimeout(hspdif
, SPDIFRX_FLAG_SYNCD
, RESET
, SPDIFRX_TIMEOUT_VALUE
, tickstart
) != HAL_OK
)
835 /* Start reception */
836 __HAL_SPDIFRX_RCV(hspdif
);
839 /* Process Unlocked */
840 __HAL_UNLOCK(hspdif
);
851 * @brief stop the audio stream receive from the Media.
852 * @param hspdif: SPDIFRX handle
855 HAL_StatusTypeDef
HAL_SPDIFRX_DMAStop(SPDIFRX_HandleTypeDef
*hspdif
)
860 /* Disable the SPDIFRX DMA requests */
861 hspdif
->Instance
->CR
&= (uint16_t)(~SPDIFRX_CR_RXDMAEN
);
862 hspdif
->Instance
->CR
&= (uint16_t)(~SPDIFRX_CR_CBDMAEN
);
864 /* Disable the SPDIFRX DMA channel */
865 __HAL_DMA_DISABLE(hspdif
->hdmaDrRx
);
866 __HAL_DMA_DISABLE(hspdif
->hdmaCsRx
);
868 /* Disable SPDIFRX peripheral */
869 __HAL_SPDIFRX_IDLE(hspdif
);
871 hspdif
->State
= HAL_SPDIFRX_STATE_READY
;
873 /* Process Unlocked */
874 __HAL_UNLOCK(hspdif
);
880 * @brief This function handles SPDIFRX interrupt request.
881 * @param hspdif: SPDIFRX handle
884 void HAL_SPDIFRX_IRQHandler(SPDIFRX_HandleTypeDef
*hspdif
)
886 /* SPDIFRX in mode Data Flow Reception ------------------------------------------------*/
887 if((__HAL_SPDIFRX_GET_FLAG(hspdif
, SPDIFRX_FLAG_RXNE
) != RESET
) && (__HAL_SPDIFRX_GET_IT_SOURCE(hspdif
, SPDIFRX_IT_RXNE
) != RESET
))
889 __HAL_SPDIFRX_CLEAR_IT(hspdif
, SPDIFRX_IT_RXNE
);
890 SPDIFRX_ReceiveDataFlow_IT(hspdif
);
893 /* SPDIFRX in mode Control Flow Reception ------------------------------------------------*/
894 if((__HAL_SPDIFRX_GET_FLAG(hspdif
, SPDIFRX_FLAG_CSRNE
) != RESET
) && (__HAL_SPDIFRX_GET_IT_SOURCE(hspdif
, SPDIFRX_IT_CSRNE
) != RESET
))
896 __HAL_SPDIFRX_CLEAR_IT(hspdif
, SPDIFRX_IT_CSRNE
);
897 SPDIFRX_ReceiveControlFlow_IT(hspdif
);
900 /* SPDIFRX Overrun error interrupt occurred ---------------------------------*/
901 if((__HAL_SPDIFRX_GET_FLAG(hspdif
, SPDIFRX_FLAG_OVR
) != RESET
) && (__HAL_SPDIFRX_GET_IT_SOURCE(hspdif
, SPDIFRX_IT_OVRIE
) != RESET
))
903 __HAL_SPDIFRX_CLEAR_IT(hspdif
, SPDIFRX_FLAG_OVR
);
905 /* Change the SPDIFRX error code */
906 hspdif
->ErrorCode
|= HAL_SPDIFRX_ERROR_OVR
;
908 /* the transfer is not stopped */
909 HAL_SPDIFRX_ErrorCallback(hspdif
);
912 /* SPDIFRX Parity error interrupt occurred ---------------------------------*/
913 if((__HAL_SPDIFRX_GET_FLAG(hspdif
, SPDIFRX_FLAG_PERR
) != RESET
) && (__HAL_SPDIFRX_GET_IT_SOURCE(hspdif
, SPDIFRX_IT_PERRIE
) != RESET
))
915 __HAL_SPDIFRX_CLEAR_IT(hspdif
, SPDIFRX_FLAG_PERR
);
917 /* Change the SPDIFRX error code */
918 hspdif
->ErrorCode
|= HAL_SPDIFRX_ERROR_PE
;
920 /* the transfer is not stopped */
921 HAL_SPDIFRX_ErrorCallback(hspdif
);
926 * @brief Rx Transfer (Data flow) half completed callbacks
927 * @param hspdif: SPDIFRX handle
930 __weak
void HAL_SPDIFRX_RxHalfCpltCallback(SPDIFRX_HandleTypeDef
*hspdif
)
932 /* Prevent unused argument(s) compilation warning */
935 /* NOTE : This function Should not be modified, when the callback is needed,
936 the HAL_SPDIFRX_RxCpltCallback could be implemented in the user file
941 * @brief Rx Transfer (Data flow) completed callbacks
942 * @param hspdif: SPDIFRX handle
945 __weak
void HAL_SPDIFRX_RxCpltCallback(SPDIFRX_HandleTypeDef
*hspdif
)
947 /* Prevent unused argument(s) compilation warning */
950 /* NOTE : This function Should not be modified, when the callback is needed,
951 the HAL_SPDIFRX_RxCpltCallback could be implemented in the user file
956 * @brief Rx (Control flow) Transfer half completed callbacks
957 * @param hspdif: SPDIFRX handle
960 __weak
void HAL_SPDIFRX_CxHalfCpltCallback(SPDIFRX_HandleTypeDef
*hspdif
)
962 /* Prevent unused argument(s) compilation warning */
965 /* NOTE : This function Should not be modified, when the callback is needed,
966 the HAL_SPDIFRX_RxCpltCallback could be implemented in the user file
971 * @brief Rx Transfer (Control flow) completed callbacks
972 * @param hspdif: SPDIFRX handle
975 __weak
void HAL_SPDIFRX_CxCpltCallback(SPDIFRX_HandleTypeDef
*hspdif
)
977 /* Prevent unused argument(s) compilation warning */
980 /* NOTE : This function Should not be modified, when the callback is needed,
981 the HAL_SPDIFRX_RxCpltCallback could be implemented in the user file
986 * @brief SPDIFRX error callbacks
987 * @param hspdif: SPDIFRX handle
990 __weak
void HAL_SPDIFRX_ErrorCallback(SPDIFRX_HandleTypeDef
*hspdif
)
992 /* Prevent unused argument(s) compilation warning */
995 /* NOTE : This function Should not be modified, when the callback is needed,
996 the HAL_SPDIFRX_ErrorCallback could be implemented in the user file
1004 /** @defgroup SPDIFRX_Exported_Functions_Group3 Peripheral State and Errors functions
1005 * @brief Peripheral State functions
1008 ===============================================================================
1009 ##### Peripheral State and Errors functions #####
1010 ===============================================================================
1012 This subsection permit to get in run-time the status of the peripheral
1020 * @brief Return the SPDIFRX state
1021 * @param hspdif : SPDIFRX handle
1024 HAL_SPDIFRX_StateTypeDef
HAL_SPDIFRX_GetState(SPDIFRX_HandleTypeDef
*hspdif
)
1026 return hspdif
->State
;
1030 * @brief Return the SPDIFRX error code
1031 * @param hspdif : SPDIFRX handle
1032 * @retval SPDIFRX Error Code
1034 uint32_t HAL_SPDIFRX_GetError(SPDIFRX_HandleTypeDef
*hspdif
)
1036 return hspdif
->ErrorCode
;
1044 * @brief DMA SPDIFRX receive process (Data flow) complete callback
1045 * @param hdma : DMA handle
1048 static void SPDIFRX_DMARxCplt(DMA_HandleTypeDef
*hdma
)
1050 SPDIFRX_HandleTypeDef
* hspdif
= ( SPDIFRX_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
1052 /* Disable Rx DMA Request */
1053 if((hdma
->Instance
->CR
& DMA_SxCR_CIRC
) == 0)
1055 hspdif
->Instance
->CR
&= (uint16_t)(~SPDIFRX_CR_RXDMAEN
);
1056 hspdif
->RxXferCount
= 0;
1057 hspdif
->State
= HAL_SPDIFRX_STATE_READY
;
1059 HAL_SPDIFRX_RxCpltCallback(hspdif
);
1063 * @brief DMA SPDIFRX receive process (Data flow) half complete callback
1064 * @param hdma : DMA handle
1067 static void SPDIFRX_DMARxHalfCplt(DMA_HandleTypeDef
*hdma
)
1069 SPDIFRX_HandleTypeDef
* hspdif
= (SPDIFRX_HandleTypeDef
*)((DMA_HandleTypeDef
*)hdma
)->Parent
;
1071 HAL_SPDIFRX_RxHalfCpltCallback(hspdif
);
1076 * @brief DMA SPDIFRX receive process (Control flow) complete callback
1077 * @param hdma : DMA handle
1080 static void SPDIFRX_DMACxCplt(DMA_HandleTypeDef
*hdma
)
1082 SPDIFRX_HandleTypeDef
* hspdif
= ( SPDIFRX_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
1084 /* Disable Cb DMA Request */
1085 hspdif
->Instance
->CR
&= (uint16_t)(~SPDIFRX_CR_CBDMAEN
);
1086 hspdif
->CsXferCount
= 0;
1088 hspdif
->State
= HAL_SPDIFRX_STATE_READY
;
1089 HAL_SPDIFRX_CxCpltCallback(hspdif
);
1093 * @brief DMA SPDIFRX receive process (Control flow) half complete callback
1094 * @param hdma : DMA handle
1097 static void SPDIFRX_DMACxHalfCplt(DMA_HandleTypeDef
*hdma
)
1099 SPDIFRX_HandleTypeDef
* hspdif
= (SPDIFRX_HandleTypeDef
*)((DMA_HandleTypeDef
*)hdma
)->Parent
;
1101 HAL_SPDIFRX_CxHalfCpltCallback(hspdif
);
1105 * @brief DMA SPDIFRX communication error callback
1106 * @param hdma : DMA handle
1109 static void SPDIFRX_DMAError(DMA_HandleTypeDef
*hdma
)
1111 SPDIFRX_HandleTypeDef
* hspdif
= ( SPDIFRX_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
1113 /* Disable Rx and Cb DMA Request */
1114 hspdif
->Instance
->CR
&= (uint16_t)(~(SPDIFRX_CR_RXDMAEN
| SPDIFRX_CR_CBDMAEN
));
1115 hspdif
->RxXferCount
= 0;
1117 hspdif
->State
= HAL_SPDIFRX_STATE_READY
;
1119 /* Set the error code and execute error callback*/
1120 hspdif
->ErrorCode
|= HAL_SPDIFRX_ERROR_DMA
;
1121 HAL_SPDIFRX_ErrorCallback(hspdif
);
1125 * @brief Receive an amount of data (Data Flow) with Interrupt
1126 * @param hspdif: SPDIFRX handle
1129 static void SPDIFRX_ReceiveDataFlow_IT(SPDIFRX_HandleTypeDef
*hspdif
)
1132 (*hspdif
->pRxBuffPtr
++) = hspdif
->Instance
->DR
;
1133 hspdif
->RxXferCount
--;
1135 if(hspdif
->RxXferCount
== 0)
1137 /* Disable RXNE/PE and OVR interrupts */
1138 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_OVRIE
| SPDIFRX_IT_PERRIE
| SPDIFRX_IT_RXNE
);
1140 hspdif
->State
= HAL_SPDIFRX_STATE_READY
;
1142 /* Process Unlocked */
1143 __HAL_UNLOCK(hspdif
);
1145 HAL_SPDIFRX_RxCpltCallback(hspdif
);
1150 * @brief Receive an amount of data (Control Flow) with Interrupt
1151 * @param hspdif: SPDIFRX handle
1154 static void SPDIFRX_ReceiveControlFlow_IT(SPDIFRX_HandleTypeDef
*hspdif
)
1157 (*hspdif
->pCsBuffPtr
++) = hspdif
->Instance
->CSR
;
1158 hspdif
->CsXferCount
--;
1160 if(hspdif
->CsXferCount
== 0)
1162 /* Disable CSRNE interrupt */
1163 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_CSRNE
);
1165 hspdif
->State
= HAL_SPDIFRX_STATE_READY
;
1167 /* Process Unlocked */
1168 __HAL_UNLOCK(hspdif
);
1170 HAL_SPDIFRX_CxCpltCallback(hspdif
);
1175 * @brief This function handles SPDIFRX Communication Timeout.
1176 * @param hspdif: SPDIFRX handle
1177 * @param Flag: Flag checked
1178 * @param Status: Value of the flag expected
1179 * @param Timeout: Duration of the timeout
1180 * @param tickstart: Tick start value
1181 * @retval HAL status
1183 static HAL_StatusTypeDef
SPDIFRX_WaitOnFlagUntilTimeout(SPDIFRX_HandleTypeDef
*hspdif
, uint32_t Flag
, FlagStatus Status
, uint32_t Timeout
, uint32_t tickstart
)
1185 /* Wait until flag is set */
1188 while(__HAL_SPDIFRX_GET_FLAG(hspdif
, Flag
) == RESET
)
1190 /* Check for the Timeout */
1191 if(Timeout
!= HAL_MAX_DELAY
)
1193 if((Timeout
== 0U)||((HAL_GetTick() - tickstart
) > Timeout
))
1195 /* Disable TXE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts for the interrupt process */
1196 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_RXNE
);
1197 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_CSRNE
);
1198 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_PERRIE
);
1199 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_OVRIE
);
1200 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_SBLKIE
);
1201 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_SYNCDIE
);
1202 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_IFEIE
);
1204 hspdif
->State
= HAL_SPDIFRX_STATE_READY
;
1206 /* Process Unlocked */
1207 __HAL_UNLOCK(hspdif
);
1216 while(__HAL_SPDIFRX_GET_FLAG(hspdif
, Flag
) != RESET
)
1218 /* Check for the Timeout */
1219 if(Timeout
!= HAL_MAX_DELAY
)
1221 if((Timeout
== 0U)||((HAL_GetTick() - tickstart
) > Timeout
))
1223 /* Disable TXE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts for the interrupt process */
1224 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_RXNE
);
1225 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_CSRNE
);
1226 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_PERRIE
);
1227 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_OVRIE
);
1228 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_SBLKIE
);
1229 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_SYNCDIE
);
1230 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_IFEIE
);
1232 hspdif
->State
= HAL_SPDIFRX_STATE_READY
;
1234 /* Process Unlocked */
1235 __HAL_UNLOCK(hspdif
);
1248 #endif /* SPDIFRX */
1249 #endif /* HAL_SPDIFRX_MODULE_ENABLED */
1258 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/