2 ******************************************************************************
3 * @file stm32f4xx_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 SPDIFRX 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 "stm32f4xx_hal.h"
127 /** @addtogroup STM32F4xx_HAL_Driver
130 /** @defgroup SPDIFRX SPDIFRX
131 * @brief SPDIFRX HAL module driver
135 #ifdef HAL_SPDIFRX_MODULE_ENABLED
137 #if defined(STM32F446xx)
139 /* Private typedef -----------------------------------------------------------*/
140 /* Private define ------------------------------------------------------------*/
141 #define SPDIFRX_TIMEOUT_VALUE 0xFFFF
143 /* Private macro -------------------------------------------------------------*/
144 /* Private variables ---------------------------------------------------------*/
145 /* Private function prototypes -----------------------------------------------*/
147 /** @addtogroup SPDIFRX_Private_Functions
150 static void SPDIFRX_DMARxCplt(DMA_HandleTypeDef
*hdma
);
151 static void SPDIFRX_DMARxHalfCplt(DMA_HandleTypeDef
*hdma
);
152 static void SPDIFRX_DMACxCplt(DMA_HandleTypeDef
*hdma
);
153 static void SPDIFRX_DMACxHalfCplt(DMA_HandleTypeDef
*hdma
);
154 static void SPDIFRX_DMAError(DMA_HandleTypeDef
*hdma
);
155 static void SPDIFRX_ReceiveControlFlow_IT(SPDIFRX_HandleTypeDef
*hspdif
);
156 static void SPDIFRX_ReceiveDataFlow_IT(SPDIFRX_HandleTypeDef
*hspdif
);
157 static HAL_StatusTypeDef
SPDIFRX_WaitOnFlagUntilTimeout(SPDIFRX_HandleTypeDef
*hspdif
, uint32_t Flag
, FlagStatus Status
, uint32_t Timeout
);
162 /* Exported functions ---------------------------------------------------------*/
164 /** @defgroup SPDIFRX_Exported_Functions SPDIFRX Exported Functions
168 /** @defgroup SPDIFRX_Exported_Functions_Group1 Initialization and de-initialization functions
169 * @brief Initialization and Configuration functions
172 ===============================================================================
173 ##### Initialization and de-initialization functions #####
174 ===============================================================================
175 [..] This subsection provides a set of functions allowing to initialize and
176 de-initialize the SPDIFRX peripheral:
178 (+) User must Implement HAL_SPDIFRX_MspInit() function in which he configures
179 all related peripherals resources (CLOCK, GPIO, DMA, IT and NVIC ).
181 (+) Call the function HAL_SPDIFRX_Init() to configure the SPDIFRX peripheral with
182 the selected configuration:
183 (++) Input Selection (IN0, IN1,...)
184 (++) Maximum allowed re-tries during synchronization phase
185 (++) Wait for activity on SPDIF selected input
186 (++) Channel status selection (from channel A or B)
187 (++) Data format (LSB, MSB, ...)
189 (++) User bits masking (PT,C,U,V,...)
191 (+) Call the function HAL_SPDIFRX_DeInit() to restore the default configuration
192 of the selected SPDIFRXx peripheral.
198 * @brief Initializes the SPDIFRX according to the specified parameters
199 * in the SPDIFRX_InitTypeDef and create the associated handle.
200 * @param hspdif: SPDIFRX handle
203 HAL_StatusTypeDef
HAL_SPDIFRX_Init(SPDIFRX_HandleTypeDef
*hspdif
)
205 uint32_t tmpreg
= 0U;
207 /* Check the SPDIFRX handle allocation */
213 /* Check the SPDIFRX parameters */
214 assert_param(IS_STEREO_MODE(hspdif
->Init
.StereoMode
));
215 assert_param(IS_SPDIFRX_INPUT_SELECT(hspdif
->Init
.InputSelection
));
216 assert_param(IS_SPDIFRX_MAX_RETRIES(hspdif
->Init
.Retries
));
217 assert_param(IS_SPDIFRX_WAIT_FOR_ACTIVITY(hspdif
->Init
.WaitForActivity
));
218 assert_param(IS_SPDIFRX_CHANNEL(hspdif
->Init
.ChannelSelection
));
219 assert_param(IS_SPDIFRX_DATA_FORMAT(hspdif
->Init
.DataFormat
));
220 assert_param(IS_PREAMBLE_TYPE_MASK(hspdif
->Init
.PreambleTypeMask
));
221 assert_param(IS_CHANNEL_STATUS_MASK(hspdif
->Init
.ChannelStatusMask
));
222 assert_param(IS_VALIDITY_MASK(hspdif
->Init
.ValidityBitMask
));
223 assert_param(IS_PARITY_ERROR_MASK(hspdif
->Init
.ParityErrorMask
));
225 if(hspdif
->State
== HAL_SPDIFRX_STATE_RESET
)
227 /* Allocate lock resource and initialize it */
228 hspdif
->Lock
= HAL_UNLOCKED
;
229 /* Init the low level hardware : GPIO, CLOCK, CORTEX...etc */
230 HAL_SPDIFRX_MspInit(hspdif
);
233 /* SPDIFRX peripheral state is BUSY*/
234 hspdif
->State
= HAL_SPDIFRX_STATE_BUSY
;
236 /* Disable SPDIFRX interface (IDLE State) */
237 __HAL_SPDIFRX_IDLE(hspdif
);
239 /* Reset the old SPDIFRX CR configuration */
240 tmpreg
= hspdif
->Instance
->CR
;
242 tmpreg
&= ~((uint16_t) SPDIFRX_CR_RXSTEO
| SPDIFRX_CR_DRFMT
| SPDIFRX_CR_PMSK
|
243 SPDIFRX_CR_VMSK
| SPDIFRX_CR_CUMSK
| SPDIFRX_CR_PTMSK
|
244 SPDIFRX_CR_CHSEL
| SPDIFRX_CR_NBTR
| SPDIFRX_CR_WFA
|
247 /* Sets the new configuration of the SPDIFRX peripheral */
248 tmpreg
|= ((uint16_t) hspdif
->Init
.StereoMode
|
249 hspdif
->Init
.InputSelection
|
250 hspdif
->Init
.Retries
|
251 hspdif
->Init
.WaitForActivity
|
252 hspdif
->Init
.ChannelSelection
|
253 hspdif
->Init
.DataFormat
|
254 hspdif
->Init
.PreambleTypeMask
|
255 hspdif
->Init
.ChannelStatusMask
|
256 hspdif
->Init
.ValidityBitMask
|
257 hspdif
->Init
.ParityErrorMask
);
259 hspdif
->Instance
->CR
= tmpreg
;
261 hspdif
->ErrorCode
= HAL_SPDIFRX_ERROR_NONE
;
263 /* SPDIFRX peripheral state is READY*/
264 hspdif
->State
= HAL_SPDIFRX_STATE_READY
;
270 * @brief DeInitializes the SPDIFRX peripheral
271 * @param hspdif: SPDIFRX handle
274 HAL_StatusTypeDef
HAL_SPDIFRX_DeInit(SPDIFRX_HandleTypeDef
*hspdif
)
276 /* Check the SPDIFRX handle allocation */
282 /* Check the parameters */
283 assert_param(IS_SPDIFRX_ALL_INSTANCE(hspdif
->Instance
));
285 hspdif
->State
= HAL_SPDIFRX_STATE_BUSY
;
287 /* Disable SPDIFRX interface (IDLE state) */
288 __HAL_SPDIFRX_IDLE(hspdif
);
290 /* DeInit the low level hardware: GPIO, CLOCK, NVIC... */
291 HAL_SPDIFRX_MspDeInit(hspdif
);
293 hspdif
->ErrorCode
= HAL_SPDIFRX_ERROR_NONE
;
295 /* SPDIFRX peripheral state is RESET*/
296 hspdif
->State
= HAL_SPDIFRX_STATE_RESET
;
299 __HAL_UNLOCK(hspdif
);
305 * @brief SPDIFRX MSP Init
306 * @param hspdif: SPDIFRX handle
309 __weak
void HAL_SPDIFRX_MspInit(SPDIFRX_HandleTypeDef
*hspdif
)
311 /* Prevent unused argument(s) compilation warning */
313 /* NOTE : This function Should not be modified, when the callback is needed,
314 the HAL_SPDIFRX_MspInit could be implemented in the user file
319 * @brief SPDIFRX MSP DeInit
320 * @param hspdif: SPDIFRX handle
323 __weak
void HAL_SPDIFRX_MspDeInit(SPDIFRX_HandleTypeDef
*hspdif
)
325 /* Prevent unused argument(s) compilation warning */
327 /* NOTE : This function Should not be modified, when the callback is needed,
328 the HAL_SPDIFRX_MspDeInit could be implemented in the user file
333 * @brief Sets the SPDIFRX dtat format according to the specified parameters
334 * in the SPDIFRX_InitTypeDef.
335 * @param hspdif: SPDIFRX handle
336 * @param sDataFormat: SPDIFRX data format
339 HAL_StatusTypeDef
HAL_SPDIFRX_SetDataFormat(SPDIFRX_HandleTypeDef
*hspdif
, SPDIFRX_SetDataFormatTypeDef sDataFormat
)
341 uint32_t tmpreg
= 0U;
343 /* Check the SPDIFRX handle allocation */
349 /* Check the SPDIFRX parameters */
350 assert_param(IS_STEREO_MODE(sDataFormat
.StereoMode
));
351 assert_param(IS_SPDIFRX_DATA_FORMAT(sDataFormat
.DataFormat
));
352 assert_param(IS_PREAMBLE_TYPE_MASK(sDataFormat
.PreambleTypeMask
));
353 assert_param(IS_CHANNEL_STATUS_MASK(sDataFormat
.ChannelStatusMask
));
354 assert_param(IS_VALIDITY_MASK(sDataFormat
.ValidityBitMask
));
355 assert_param(IS_PARITY_ERROR_MASK(sDataFormat
.ParityErrorMask
));
357 /* Reset the old SPDIFRX CR configuration */
358 tmpreg
= hspdif
->Instance
->CR
;
360 if(((tmpreg
& SPDIFRX_STATE_RCV
) == SPDIFRX_STATE_RCV
) &&
361 (((tmpreg
& SPDIFRX_CR_DRFMT
) != sDataFormat
.DataFormat
) ||
362 ((tmpreg
& SPDIFRX_CR_RXSTEO
) != sDataFormat
.StereoMode
)))
367 tmpreg
&= ~((uint16_t) SPDIFRX_CR_RXSTEO
| SPDIFRX_CR_DRFMT
| SPDIFRX_CR_PMSK
|
368 SPDIFRX_CR_VMSK
| SPDIFRX_CR_CUMSK
| SPDIFRX_CR_PTMSK
);
370 /* Sets the new configuration of the SPDIFRX peripheral */
371 tmpreg
|= ((uint16_t) sDataFormat
.StereoMode
|
372 sDataFormat
.DataFormat
|
373 sDataFormat
.PreambleTypeMask
|
374 sDataFormat
.ChannelStatusMask
|
375 sDataFormat
.ValidityBitMask
|
376 sDataFormat
.ParityErrorMask
);
378 hspdif
->Instance
->CR
= tmpreg
;
387 /** @defgroup SPDIFRX_Exported_Functions_Group2 IO operation functions
388 * @brief Data transfers functions
391 ===============================================================================
392 ##### IO operation functions #####
393 ===============================================================================
395 This subsection provides a set of functions allowing to manage the SPDIFRX data
398 (#) There is two mode of transfer:
399 (++) Blocking mode : The communication is performed in the polling mode.
400 The status of all data processing is returned by the same function
401 after finishing transfer.
402 (++) No-Blocking mode : The communication is performed using Interrupts
403 or DMA. These functions return the status of the transfer start-up.
404 The end of the data processing will be indicated through the
405 dedicated SPDIFRX IRQ when using Interrupt mode or the DMA IRQ when
408 (#) Blocking mode functions are :
409 (++) HAL_SPDIFRX_ReceiveDataFlow()
410 (++) HAL_SPDIFRX_ReceiveControlFlow()
411 (+@) Do not use blocking mode to receive both control and data flow at the same time.
413 (#) No-Blocking mode functions with Interrupt are :
414 (++) HAL_SPDIFRX_ReceiveControlFlow_IT()
415 (++) HAL_SPDIFRX_ReceiveDataFlow_IT()
417 (#) No-Blocking mode functions with DMA are :
418 (++) HAL_SPDIFRX_ReceiveControlFlow_DMA()
419 (++) HAL_SPDIFRX_ReceiveDataFlow_DMA()
421 (#) A set of Transfer Complete Callbacks are provided in No_Blocking mode:
422 (++) HAL_SPDIFRX_RxCpltCallback()
423 (++) HAL_SPDIFRX_ErrorCallback()
430 * @brief Receives an amount of data (Data Flow) in blocking mode.
431 * @param hspdif: pointer to SPDIFRX_HandleTypeDef structure that contains
432 * the configuration information for SPDIFRX module.
433 * @param pData: Pointer to data buffer
434 * @param Size: Amount of data to be received
435 * @param Timeout: Timeout duration
438 HAL_StatusTypeDef
HAL_SPDIFRX_ReceiveDataFlow(SPDIFRX_HandleTypeDef
*hspdif
, uint32_t *pData
, uint16_t Size
, uint32_t Timeout
)
440 if((pData
== NULL
) || (Size
== 0))
445 if(hspdif
->State
== HAL_SPDIFRX_STATE_READY
)
450 hspdif
->State
= HAL_SPDIFRX_STATE_BUSY
;
452 /* Start synchronisation */
453 __HAL_SPDIFRX_SYNC(hspdif
);
455 /* Wait until SYNCD flag is set */
456 if(SPDIFRX_WaitOnFlagUntilTimeout(hspdif
, SPDIFRX_FLAG_SYNCD
, RESET
, Timeout
) != HAL_OK
)
461 /* Start reception */
462 __HAL_SPDIFRX_RCV(hspdif
);
464 /* Receive data flow */
467 /* Wait until RXNE flag is set */
468 if(SPDIFRX_WaitOnFlagUntilTimeout(hspdif
, SPDIFRX_FLAG_RXNE
, RESET
, Timeout
) != HAL_OK
)
473 (*pData
++) = hspdif
->Instance
->DR
;
478 hspdif
->State
= HAL_SPDIFRX_STATE_READY
;
480 /* Process Unlocked */
481 __HAL_UNLOCK(hspdif
);
492 * @brief Receives an amount of data (Control Flow) in blocking mode.
493 * @param hspdif: pointer to a SPDIFRX_HandleTypeDef structure that contains
494 * the configuration information for SPDIFRX module.
495 * @param pData: Pointer to data buffer
496 * @param Size: Amount of data to be received
497 * @param Timeout: Timeout duration
500 HAL_StatusTypeDef
HAL_SPDIFRX_ReceiveControlFlow(SPDIFRX_HandleTypeDef
*hspdif
, uint32_t *pData
, uint16_t Size
, uint32_t Timeout
)
502 if((pData
== NULL
) || (Size
== 0))
507 if(hspdif
->State
== HAL_SPDIFRX_STATE_READY
)
512 hspdif
->State
= HAL_SPDIFRX_STATE_BUSY
;
514 /* Start synchronization */
515 __HAL_SPDIFRX_SYNC(hspdif
);
517 /* Wait until SYNCD flag is set */
518 if(SPDIFRX_WaitOnFlagUntilTimeout(hspdif
, SPDIFRX_FLAG_SYNCD
, RESET
, Timeout
) != HAL_OK
)
523 /* Start reception */
524 __HAL_SPDIFRX_RCV(hspdif
);
526 /* Receive control flow */
529 /* Wait until CSRNE flag is set */
530 if(SPDIFRX_WaitOnFlagUntilTimeout(hspdif
, SPDIFRX_FLAG_CSRNE
, RESET
, Timeout
) != HAL_OK
)
535 (*pData
++) = hspdif
->Instance
->CSR
;
540 hspdif
->State
= HAL_SPDIFRX_STATE_READY
;
542 /* Process Unlocked */
543 __HAL_UNLOCK(hspdif
);
553 * @brief Receive an amount of data (Data Flow) in non-blocking mode with Interrupt
554 * @param hspdif: SPDIFRX handle
555 * @param pData: a 32-bit pointer to the Receive data buffer.
556 * @param Size: number of data sample to be received .
559 HAL_StatusTypeDef
HAL_SPDIFRX_ReceiveDataFlow_IT(SPDIFRX_HandleTypeDef
*hspdif
, uint32_t *pData
, uint16_t Size
)
561 __IO
uint32_t count
= SPDIFRX_TIMEOUT_VALUE
* (SystemCoreClock
/ 24U / 1000U);
563 if((hspdif
->State
== HAL_SPDIFRX_STATE_READY
) || (hspdif
->State
== HAL_SPDIFRX_STATE_BUSY_CX
))
565 if((pData
== NULL
) || (Size
== 0))
573 hspdif
->pRxBuffPtr
= pData
;
574 hspdif
->RxXferSize
= Size
;
575 hspdif
->RxXferCount
= Size
;
577 hspdif
->ErrorCode
= HAL_SPDIFRX_ERROR_NONE
;
579 /* Check if a receive process is ongoing or not */
580 hspdif
->State
= HAL_SPDIFRX_STATE_BUSY_RX
;
582 /* Enable the SPDIFRX PE Error Interrupt */
583 __HAL_SPDIFRX_ENABLE_IT(hspdif
, SPDIFRX_IT_PERRIE
);
585 /* Enable the SPDIFRX OVR Error Interrupt */
586 __HAL_SPDIFRX_ENABLE_IT(hspdif
, SPDIFRX_IT_OVRIE
);
588 /* Process Unlocked */
589 __HAL_UNLOCK(hspdif
);
591 /* Enable the SPDIFRX RXNE interrupt */
592 __HAL_SPDIFRX_ENABLE_IT(hspdif
, SPDIFRX_IT_RXNE
);
594 if ((SPDIFRX
->CR
& SPDIFRX_CR_SPDIFEN
) != SPDIFRX_STATE_SYNC
|| (SPDIFRX
->CR
& SPDIFRX_CR_SPDIFEN
) != 0x00U
)
596 /* Start synchronization */
597 __HAL_SPDIFRX_SYNC(hspdif
);
599 /* Wait until SYNCD flag is set */
604 /* Disable TXE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts for the interrupt process */
605 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_RXNE
);
606 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_CSRNE
);
607 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_PERRIE
);
608 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_OVRIE
);
609 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_SBLKIE
);
610 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_SYNCDIE
);
611 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_IFEIE
);
613 hspdif
->State
= HAL_SPDIFRX_STATE_READY
;
615 /* Process Unlocked */
616 __HAL_UNLOCK(hspdif
);
621 while (__HAL_SPDIFRX_GET_FLAG(hspdif
, SPDIFRX_FLAG_SYNCD
) == RESET
);
623 /* Start reception */
624 __HAL_SPDIFRX_RCV(hspdif
);
636 * @brief Receive an amount of data (Control Flow) with Interrupt
637 * @param hspdif: SPDIFRX handle
638 * @param pData: a 32-bit pointer to the Receive data buffer.
639 * @param Size: number of data sample (Control Flow) to be received :
642 HAL_StatusTypeDef
HAL_SPDIFRX_ReceiveControlFlow_IT(SPDIFRX_HandleTypeDef
*hspdif
, uint32_t *pData
, uint16_t Size
)
644 __IO
uint32_t count
= SPDIFRX_TIMEOUT_VALUE
* (SystemCoreClock
/ 24U / 1000U);
646 if((hspdif
->State
== HAL_SPDIFRX_STATE_READY
) || (hspdif
->State
== HAL_SPDIFRX_STATE_BUSY_RX
))
648 if((pData
== NULL
) || (Size
== 0))
656 hspdif
->pCsBuffPtr
= pData
;
657 hspdif
->CsXferSize
= Size
;
658 hspdif
->CsXferCount
= Size
;
660 hspdif
->ErrorCode
= HAL_SPDIFRX_ERROR_NONE
;
662 /* Check if a receive process is ongoing or not */
663 hspdif
->State
= HAL_SPDIFRX_STATE_BUSY_CX
;
665 /* Enable the SPDIFRX PE Error Interrupt */
666 __HAL_SPDIFRX_ENABLE_IT(hspdif
, SPDIFRX_IT_PERRIE
);
668 /* Enable the SPDIFRX OVR Error Interrupt */
669 __HAL_SPDIFRX_ENABLE_IT(hspdif
, SPDIFRX_IT_OVRIE
);
671 /* Process Unlocked */
672 __HAL_UNLOCK(hspdif
);
674 /* Enable the SPDIFRX CSRNE interrupt */
675 __HAL_SPDIFRX_ENABLE_IT(hspdif
, SPDIFRX_IT_CSRNE
);
677 if ((SPDIFRX
->CR
& SPDIFRX_CR_SPDIFEN
) != SPDIFRX_STATE_SYNC
|| (SPDIFRX
->CR
& SPDIFRX_CR_SPDIFEN
) != 0x00U
)
679 /* Start synchronization */
680 __HAL_SPDIFRX_SYNC(hspdif
);
682 /* Wait until SYNCD flag is set */
687 /* Disable TXE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts for the interrupt process */
688 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_RXNE
);
689 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_CSRNE
);
690 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_PERRIE
);
691 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_OVRIE
);
692 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_SBLKIE
);
693 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_SYNCDIE
);
694 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_IFEIE
);
696 hspdif
->State
= HAL_SPDIFRX_STATE_READY
;
698 /* Process Unlocked */
699 __HAL_UNLOCK(hspdif
);
704 while (__HAL_SPDIFRX_GET_FLAG(hspdif
, SPDIFRX_FLAG_SYNCD
) == RESET
);
706 /* Start reception */
707 __HAL_SPDIFRX_RCV(hspdif
);
719 * @brief Receive an amount of data (Data Flow) mode with DMA
720 * @param hspdif: SPDIFRX handle
721 * @param pData: a 32-bit pointer to the Receive data buffer.
722 * @param Size: number of data sample to be received :
725 HAL_StatusTypeDef
HAL_SPDIFRX_ReceiveDataFlow_DMA(SPDIFRX_HandleTypeDef
*hspdif
, uint32_t *pData
, uint16_t Size
)
727 __IO
uint32_t count
= SPDIFRX_TIMEOUT_VALUE
* (SystemCoreClock
/ 24U / 1000U);
729 if((pData
== NULL
) || (Size
== 0))
734 if((hspdif
->State
== HAL_SPDIFRX_STATE_READY
) || (hspdif
->State
== HAL_SPDIFRX_STATE_BUSY_CX
))
736 hspdif
->pRxBuffPtr
= pData
;
737 hspdif
->RxXferSize
= Size
;
738 hspdif
->RxXferCount
= Size
;
743 hspdif
->ErrorCode
= HAL_SPDIFRX_ERROR_NONE
;
744 hspdif
->State
= HAL_SPDIFRX_STATE_BUSY_RX
;
746 /* Set the SPDIFRX Rx DMA Half transfer complete callback */
747 hspdif
->hdmaDrRx
->XferHalfCpltCallback
= SPDIFRX_DMARxHalfCplt
;
749 /* Set the SPDIFRX Rx DMA transfer complete callback */
750 hspdif
->hdmaDrRx
->XferCpltCallback
= SPDIFRX_DMARxCplt
;
752 /* Set the DMA error callback */
753 hspdif
->hdmaDrRx
->XferErrorCallback
= SPDIFRX_DMAError
;
755 /* Enable the DMA request */
756 HAL_DMA_Start_IT(hspdif
->hdmaDrRx
, (uint32_t)&hspdif
->Instance
->DR
, (uint32_t)hspdif
->pRxBuffPtr
, Size
);
758 /* Enable RXDMAEN bit in SPDIFRX CR register for data flow reception*/
759 hspdif
->Instance
->CR
|= SPDIFRX_CR_RXDMAEN
;
761 if ((SPDIFRX
->CR
& SPDIFRX_CR_SPDIFEN
) != SPDIFRX_STATE_SYNC
|| (SPDIFRX
->CR
& SPDIFRX_CR_SPDIFEN
) != 0x00U
)
763 /* Start synchronization */
764 __HAL_SPDIFRX_SYNC(hspdif
);
766 /* Wait until SYNCD flag is set */
771 /* Disable TXE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts for the interrupt process */
772 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_RXNE
);
773 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_CSRNE
);
774 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_PERRIE
);
775 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_OVRIE
);
776 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_SBLKIE
);
777 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_SYNCDIE
);
778 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_IFEIE
);
780 hspdif
->State
= HAL_SPDIFRX_STATE_READY
;
782 /* Process Unlocked */
783 __HAL_UNLOCK(hspdif
);
788 while (__HAL_SPDIFRX_GET_FLAG(hspdif
, SPDIFRX_FLAG_SYNCD
) == RESET
);
790 /* Start reception */
791 __HAL_SPDIFRX_RCV(hspdif
);
794 /* Process Unlocked */
795 __HAL_UNLOCK(hspdif
);
806 * @brief Receive an amount of data (Control Flow) with DMA
807 * @param hspdif: SPDIFRX handle
808 * @param pData: a 32-bit pointer to the Receive data buffer.
809 * @param Size: number of data (Control Flow) sample to be received :
812 HAL_StatusTypeDef
HAL_SPDIFRX_ReceiveControlFlow_DMA(SPDIFRX_HandleTypeDef
*hspdif
, uint32_t *pData
, uint16_t Size
)
814 __IO
uint32_t count
= SPDIFRX_TIMEOUT_VALUE
* (SystemCoreClock
/ 24U / 1000U);
816 if((pData
== NULL
) || (Size
== 0))
821 if((hspdif
->State
== HAL_SPDIFRX_STATE_READY
) || (hspdif
->State
== HAL_SPDIFRX_STATE_BUSY_RX
))
823 hspdif
->pCsBuffPtr
= pData
;
824 hspdif
->CsXferSize
= Size
;
825 hspdif
->CsXferCount
= Size
;
830 hspdif
->ErrorCode
= HAL_SPDIFRX_ERROR_NONE
;
831 hspdif
->State
= HAL_SPDIFRX_STATE_BUSY_CX
;
833 /* Set the SPDIFRX Rx DMA Half transfer complete callback */
834 hspdif
->hdmaCsRx
->XferHalfCpltCallback
= SPDIFRX_DMACxHalfCplt
;
836 /* Set the SPDIFRX Rx DMA transfer complete callback */
837 hspdif
->hdmaCsRx
->XferCpltCallback
= SPDIFRX_DMACxCplt
;
839 /* Set the DMA error callback */
840 hspdif
->hdmaCsRx
->XferErrorCallback
= SPDIFRX_DMAError
;
842 /* Enable the DMA request */
843 HAL_DMA_Start_IT(hspdif
->hdmaCsRx
, (uint32_t)&hspdif
->Instance
->CSR
, (uint32_t)hspdif
->pCsBuffPtr
, Size
);
845 /* Enable CBDMAEN bit in SPDIFRX CR register for control flow reception*/
846 hspdif
->Instance
->CR
|= SPDIFRX_CR_CBDMAEN
;
848 if ((SPDIFRX
->CR
& SPDIFRX_CR_SPDIFEN
) != SPDIFRX_STATE_SYNC
|| (SPDIFRX
->CR
& SPDIFRX_CR_SPDIFEN
) != 0x00U
)
850 /* Start synchronization */
851 __HAL_SPDIFRX_SYNC(hspdif
);
853 /* Wait until SYNCD flag is set */
858 /* Disable TXE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts for the interrupt process */
859 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_RXNE
);
860 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_CSRNE
);
861 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_PERRIE
);
862 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_OVRIE
);
863 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_SBLKIE
);
864 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_SYNCDIE
);
865 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_IFEIE
);
867 hspdif
->State
= HAL_SPDIFRX_STATE_READY
;
869 /* Process Unlocked */
870 __HAL_UNLOCK(hspdif
);
875 while (__HAL_SPDIFRX_GET_FLAG(hspdif
, SPDIFRX_FLAG_SYNCD
) == RESET
);
877 /* Start reception */
878 __HAL_SPDIFRX_RCV(hspdif
);
881 /* Process Unlocked */
882 __HAL_UNLOCK(hspdif
);
893 * @brief stop the audio stream receive from the Media.
894 * @param hspdif: SPDIFRX handle
897 HAL_StatusTypeDef
HAL_SPDIFRX_DMAStop(SPDIFRX_HandleTypeDef
*hspdif
)
902 /* Disable the SPDIFRX DMA requests */
903 hspdif
->Instance
->CR
&= (uint16_t)(~SPDIFRX_CR_RXDMAEN
);
904 hspdif
->Instance
->CR
&= (uint16_t)(~SPDIFRX_CR_CBDMAEN
);
906 /* Disable the SPDIFRX DMA channel */
907 __HAL_DMA_DISABLE(hspdif
->hdmaDrRx
);
908 __HAL_DMA_DISABLE(hspdif
->hdmaCsRx
);
910 /* Disable SPDIFRX peripheral */
911 __HAL_SPDIFRX_IDLE(hspdif
);
913 hspdif
->State
= HAL_SPDIFRX_STATE_READY
;
915 /* Process Unlocked */
916 __HAL_UNLOCK(hspdif
);
922 * @brief This function handles SPDIFRX interrupt request.
923 * @param hspdif: SPDIFRX handle
926 void HAL_SPDIFRX_IRQHandler(SPDIFRX_HandleTypeDef
*hspdif
)
928 /* SPDIFRX in mode Data Flow Reception ------------------------------------------------*/
929 if((__HAL_SPDIFRX_GET_FLAG(hspdif
, SPDIFRX_FLAG_RXNE
) != RESET
) && (__HAL_SPDIFRX_GET_IT_SOURCE(hspdif
, SPDIFRX_IT_RXNE
) != RESET
))
931 __HAL_SPDIFRX_CLEAR_IT(hspdif
, SPDIFRX_IT_RXNE
);
932 SPDIFRX_ReceiveDataFlow_IT(hspdif
);
935 /* SPDIFRX in mode Control Flow Reception ------------------------------------------------*/
936 if((__HAL_SPDIFRX_GET_FLAG(hspdif
, SPDIFRX_FLAG_CSRNE
) != RESET
) && (__HAL_SPDIFRX_GET_IT_SOURCE(hspdif
, SPDIFRX_IT_CSRNE
) != RESET
))
938 __HAL_SPDIFRX_CLEAR_IT(hspdif
, SPDIFRX_IT_CSRNE
);
939 SPDIFRX_ReceiveControlFlow_IT(hspdif
);
942 /* SPDIFRX Overrun error interrupt occurred ---------------------------------*/
943 if((__HAL_SPDIFRX_GET_FLAG(hspdif
, SPDIFRX_FLAG_OVR
) != RESET
) && (__HAL_SPDIFRX_GET_IT_SOURCE(hspdif
, SPDIFRX_IT_OVRIE
) != RESET
))
945 __HAL_SPDIFRX_CLEAR_IT(hspdif
, SPDIFRX_FLAG_OVR
);
947 /* Change the SPDIFRX error code */
948 hspdif
->ErrorCode
|= HAL_SPDIFRX_ERROR_OVR
;
950 /* the transfer is not stopped */
951 HAL_SPDIFRX_ErrorCallback(hspdif
);
954 /* SPDIFRX Parity error interrupt occurred ---------------------------------*/
955 if((__HAL_SPDIFRX_GET_FLAG(hspdif
, SPDIFRX_FLAG_PERR
) != RESET
) && (__HAL_SPDIFRX_GET_IT_SOURCE(hspdif
, SPDIFRX_IT_PERRIE
) != RESET
))
957 __HAL_SPDIFRX_CLEAR_IT(hspdif
, SPDIFRX_FLAG_PERR
);
959 /* Change the SPDIFRX error code */
960 hspdif
->ErrorCode
|= HAL_SPDIFRX_ERROR_PE
;
962 /* the transfer is not stopped */
963 HAL_SPDIFRX_ErrorCallback(hspdif
);
968 * @brief Rx Transfer (Data flow) half completed callbacks
969 * @param hspdif: SPDIFRX handle
972 __weak
void HAL_SPDIFRX_RxHalfCpltCallback(SPDIFRX_HandleTypeDef
*hspdif
)
974 /* Prevent unused argument(s) compilation warning */
976 /* NOTE : This function Should not be modified, when the callback is needed,
977 the HAL_SPDIFRX_RxCpltCallback could be implemented in the user file
982 * @brief Rx Transfer (Data flow) completed callbacks
983 * @param hspdif: SPDIFRX handle
986 __weak
void HAL_SPDIFRX_RxCpltCallback(SPDIFRX_HandleTypeDef
*hspdif
)
988 /* Prevent unused argument(s) compilation warning */
990 /* NOTE : This function Should not be modified, when the callback is needed,
991 the HAL_SPDIFRX_RxCpltCallback could be implemented in the user file
996 * @brief Rx (Control flow) Transfer half completed callbacks
997 * @param hspdif: SPDIFRX handle
1000 __weak
void HAL_SPDIFRX_CxHalfCpltCallback(SPDIFRX_HandleTypeDef
*hspdif
)
1002 /* Prevent unused argument(s) compilation warning */
1004 /* NOTE : This function Should not be modified, when the callback is needed,
1005 the HAL_SPDIFRX_RxCpltCallback could be implemented in the user file
1010 * @brief Rx Transfer (Control flow) completed callbacks
1011 * @param hspdif: SPDIFRX handle
1014 __weak
void HAL_SPDIFRX_CxCpltCallback(SPDIFRX_HandleTypeDef
*hspdif
)
1016 /* Prevent unused argument(s) compilation warning */
1018 /* NOTE : This function Should not be modified, when the callback is needed,
1019 the HAL_SPDIFRX_RxCpltCallback could be implemented in the user file
1024 * @brief SPDIFRX error callbacks
1025 * @param hspdif: SPDIFRX handle
1028 __weak
void HAL_SPDIFRX_ErrorCallback(SPDIFRX_HandleTypeDef
*hspdif
)
1030 /* Prevent unused argument(s) compilation warning */
1032 /* NOTE : This function Should not be modified, when the callback is needed,
1033 the HAL_SPDIFRX_ErrorCallback could be implemented in the user file
1041 /** @defgroup SPDIFRX_Exported_Functions_Group3 Peripheral State and Errors functions
1042 * @brief Peripheral State functions
1045 ===============================================================================
1046 ##### Peripheral State and Errors functions #####
1047 ===============================================================================
1049 This subsection permit to get in run-time the status of the peripheral
1057 * @brief Return the SPDIFRX state
1058 * @param hspdif : SPDIFRX handle
1061 HAL_SPDIFRX_StateTypeDef
HAL_SPDIFRX_GetState(SPDIFRX_HandleTypeDef
*hspdif
)
1063 return hspdif
->State
;
1067 * @brief Return the SPDIFRX error code
1068 * @param hspdif : SPDIFRX handle
1069 * @retval SPDIFRX Error Code
1071 uint32_t HAL_SPDIFRX_GetError(SPDIFRX_HandleTypeDef
*hspdif
)
1073 return hspdif
->ErrorCode
;
1081 * @brief DMA SPDIFRX receive process (Data flow) complete callback
1082 * @param hdma : DMA handle
1085 static void SPDIFRX_DMARxCplt(DMA_HandleTypeDef
*hdma
)
1087 SPDIFRX_HandleTypeDef
* hspdif
= ( SPDIFRX_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
1089 /* Disable Rx DMA Request */
1090 hspdif
->Instance
->CR
&= (uint16_t)(~SPDIFRX_CR_RXDMAEN
);
1091 hspdif
->RxXferCount
= 0U;
1093 hspdif
->State
= HAL_SPDIFRX_STATE_READY
;
1094 HAL_SPDIFRX_RxCpltCallback(hspdif
);
1098 * @brief DMA SPDIFRX receive process (Data flow) half complete callback
1099 * @param hdma : DMA handle
1102 static void SPDIFRX_DMARxHalfCplt(DMA_HandleTypeDef
*hdma
)
1104 SPDIFRX_HandleTypeDef
* hspdif
= (SPDIFRX_HandleTypeDef
*)((DMA_HandleTypeDef
*)hdma
)->Parent
;
1106 HAL_SPDIFRX_RxHalfCpltCallback(hspdif
);
1110 * @brief DMA SPDIFRX receive process (Control flow) complete callback
1111 * @param hdma : DMA handle
1114 static void SPDIFRX_DMACxCplt(DMA_HandleTypeDef
*hdma
)
1116 SPDIFRX_HandleTypeDef
* hspdif
= ( SPDIFRX_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
1118 /* Disable Cb DMA Request */
1119 hspdif
->Instance
->CR
&= (uint16_t)(~SPDIFRX_CR_CBDMAEN
);
1120 hspdif
->CsXferCount
= 0U;
1122 hspdif
->State
= HAL_SPDIFRX_STATE_READY
;
1123 HAL_SPDIFRX_CxCpltCallback(hspdif
);
1127 * @brief DMA SPDIFRX receive process (Control flow) half complete callback
1128 * @param hdma : DMA handle
1131 static void SPDIFRX_DMACxHalfCplt(DMA_HandleTypeDef
*hdma
)
1133 SPDIFRX_HandleTypeDef
* hspdif
= (SPDIFRX_HandleTypeDef
*)((DMA_HandleTypeDef
*)hdma
)->Parent
;
1135 HAL_SPDIFRX_CxHalfCpltCallback(hspdif
);
1139 * @brief DMA SPDIFRX communication error callback
1140 * @param hdma : DMA handle
1143 static void SPDIFRX_DMAError(DMA_HandleTypeDef
*hdma
)
1145 SPDIFRX_HandleTypeDef
* hspdif
= ( SPDIFRX_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
1147 /* Disable Rx and Cb DMA Request */
1148 hspdif
->Instance
->CR
&= (uint16_t)(~(SPDIFRX_CR_RXDMAEN
| SPDIFRX_CR_CBDMAEN
));
1149 hspdif
->RxXferCount
= 0U;
1151 hspdif
->State
= HAL_SPDIFRX_STATE_READY
;
1153 /* Set the error code and execute error callback*/
1154 hspdif
->ErrorCode
|= HAL_SPDIFRX_ERROR_DMA
;
1155 HAL_SPDIFRX_ErrorCallback(hspdif
);
1159 * @brief Receive an amount of data (Data Flow) with Interrupt
1160 * @param hspdif: SPDIFRX handle
1163 static void SPDIFRX_ReceiveDataFlow_IT(SPDIFRX_HandleTypeDef
*hspdif
)
1166 (*hspdif
->pRxBuffPtr
++) = hspdif
->Instance
->DR
;
1167 hspdif
->RxXferCount
--;
1169 if(hspdif
->RxXferCount
== 0U)
1171 /* Disable RXNE/PE and OVR interrupts */
1172 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_OVRIE
| SPDIFRX_IT_PERRIE
| SPDIFRX_IT_RXNE
);
1174 hspdif
->State
= HAL_SPDIFRX_STATE_READY
;
1176 /* Process Unlocked */
1177 __HAL_UNLOCK(hspdif
);
1179 HAL_SPDIFRX_RxCpltCallback(hspdif
);
1184 * @brief Receive an amount of data (Control Flow) with Interrupt
1185 * @param hspdif: SPDIFRX handle
1188 static void SPDIFRX_ReceiveControlFlow_IT(SPDIFRX_HandleTypeDef
*hspdif
)
1191 (*hspdif
->pCsBuffPtr
++) = hspdif
->Instance
->CSR
;
1192 hspdif
->CsXferCount
--;
1194 if(hspdif
->CsXferCount
== 0U)
1196 /* Disable CSRNE interrupt */
1197 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_CSRNE
);
1199 hspdif
->State
= HAL_SPDIFRX_STATE_READY
;
1201 /* Process Unlocked */
1202 __HAL_UNLOCK(hspdif
);
1204 HAL_SPDIFRX_CxCpltCallback(hspdif
);
1209 * @brief This function handles SPDIFRX Communication Timeout.
1210 * @param hspdif: SPDIFRX handle
1211 * @param Flag: Flag checked
1212 * @param Status: Value of the flag expected
1213 * @param Timeout: Duration of the timeout
1214 * @retval HAL status
1216 static HAL_StatusTypeDef
SPDIFRX_WaitOnFlagUntilTimeout(SPDIFRX_HandleTypeDef
*hspdif
, uint32_t Flag
, FlagStatus Status
, uint32_t Timeout
)
1218 uint32_t tickstart
= 0U;
1221 tickstart
= HAL_GetTick();
1223 /* Wait until flag is set */
1226 while(__HAL_SPDIFRX_GET_FLAG(hspdif
, Flag
) == RESET
)
1228 /* Check for the Timeout */
1229 if(Timeout
!= HAL_MAX_DELAY
)
1231 if((Timeout
== 0U)||((HAL_GetTick() - tickstart
) > Timeout
))
1233 /* Disable TXE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts for the interrupt process */
1234 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_RXNE
);
1235 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_CSRNE
);
1236 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_PERRIE
);
1237 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_OVRIE
);
1238 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_SBLKIE
);
1239 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_SYNCDIE
);
1240 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_IFEIE
);
1242 hspdif
->State
= HAL_SPDIFRX_STATE_READY
;
1244 /* Process Unlocked */
1245 __HAL_UNLOCK(hspdif
);
1254 while(__HAL_SPDIFRX_GET_FLAG(hspdif
, Flag
) != RESET
)
1256 /* Check for the Timeout */
1257 if(Timeout
!= HAL_MAX_DELAY
)
1259 if((Timeout
== 0U)||((HAL_GetTick() - tickstart
) > Timeout
))
1261 /* Disable TXE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts for the interrupt process */
1262 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_RXNE
);
1263 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_CSRNE
);
1264 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_PERRIE
);
1265 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_OVRIE
);
1266 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_SBLKIE
);
1267 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_SYNCDIE
);
1268 __HAL_SPDIFRX_DISABLE_IT(hspdif
, SPDIFRX_IT_IFEIE
);
1270 hspdif
->State
= HAL_SPDIFRX_STATE_READY
;
1272 /* Process Unlocked */
1273 __HAL_UNLOCK(hspdif
);
1286 #endif /* STM32F446xx */
1288 #endif /* HAL_SPDIFRX_MODULE_ENABLED */
1297 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/