F1 and F3 HAL / LL libraries
[betaflight.git] / lib / main / STM32F3 / Drivers / STM32F3xx_HAL_Driver / Src / stm32f3xx_hal_i2s.c
blobbdfb602441a77344832d2195c6bb906d94e4c06c
1 /**
2 ******************************************************************************
3 * @file stm32f3xx_hal_i2s.c
4 * @author MCD Application Team
5 * @brief I2S HAL module driver.
6 * This file provides firmware functions to manage the following
7 * functionalities of the Integrated Interchip Sound (I2S) peripheral:
8 * + Initialization and de-initialization functions
9 * + IO operation functions
10 * + Peripheral State and Errors functions
11 @verbatim
12 ===============================================================================
13 ##### How to use this driver #####
14 ===============================================================================
15 [..]
16 The I2S HAL driver can be used as follows:
18 (#) Declare a I2S_HandleTypeDef handle structure.
19 (#) Initialize the I2S low level resources by implement the HAL_I2S_MspInit() API:
20 (##) Enable the SPIx interface clock.
21 (##) I2S pins configuration:
22 (+++) Enable the clock for the I2S GPIOs.
23 (+++) Configure these I2S pins as alternate function pull-up.
24 (##) NVIC configuration if you need to use interrupt process (HAL_I2S_Transmit_IT()
25 and HAL_I2S_Receive_IT() APIs).
26 (+++) Configure the I2Sx interrupt priority.
27 (+++) Enable the NVIC I2S IRQ handle.
28 (##) DMA Configuration if you need to use DMA process (HAL_I2S_Transmit_DMA()
29 and HAL_I2S_Receive_DMA() APIs:
30 (+++) Declare a DMA handle structure for the Tx/Rx channel.
31 (+++) Enable the DMAx interface clock.
32 (+++) Configure the declared DMA handle structure with the required Tx/Rx parameters.
33 (+++) Configure the DMA Tx/Rx Channel.
34 (+++) Associate the initilalized DMA handle to the I2S DMA Tx/Rx handle.
35 (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on the
36 DMA Tx/Rx Channel.
38 (#) Program the Mode, Standard, Data Format, MCLK Output, Audio frequency and Polarity
39 using HAL_I2S_Init() function.
41 -@- The specific I2S interrupts (Transmission complete interrupt,
42 RXNE interrupt and Error Interrupts) will be managed using the macros
43 __HAL_I2S_ENABLE_IT() and __HAL_I2S_DISABLE_IT() inside the transmit and receive process.
44 -@- Make sure that either:
45 (+@) I2S clock is configured based on SYSCLK or
46 (+@) External clock source is configured after setting correctly
47 the define constant EXTERNAL_CLOCK_VALUE in the stm32f3xx_hal_conf.h file.
49 (#) Three mode of operations are available within this driver :
51 *** Polling mode IO operation ***
52 =================================
53 [..]
54 (+) Send an amount of data in blocking mode using HAL_I2S_Transmit()
55 (+) Receive an amount of data in blocking mode using HAL_I2S_Receive()
57 *** Interrupt mode IO operation ***
58 ===================================
59 [..]
60 (+) Send an amount of data in non blocking mode using HAL_I2S_Transmit_IT()
61 (+) At transmission end of half transfer HAL_I2S_TxHalfCpltCallback is executed and user can
62 add his own code by customization of function pointer HAL_I2S_TxHalfCpltCallback
63 (+) At transmission end of transfer HAL_I2S_TxCpltCallback is executed and user can
64 add his own code by customization of function pointer HAL_I2S_TxCpltCallback
65 (+) Receive an amount of data in non blocking mode using HAL_I2S_Receive_IT()
66 (+) At reception end of half transfer HAL_I2S_RxHalfCpltCallback is executed and user can
67 add his own code by customization of function pointer HAL_I2S_RxHalfCpltCallback
68 (+) At reception end of transfer HAL_I2S_RxCpltCallback is executed and user can
69 add his own code by customization of function pointer HAL_I2S_RxCpltCallback
70 (+) In case of transfer Error, HAL_I2S_ErrorCallback() function is executed and user can
71 add his own code by customization of function pointer HAL_I2S_ErrorCallback
73 *** DMA mode IO operation ***
74 ==============================
75 [..]
76 (+) Send an amount of data in non blocking mode (DMA) using HAL_I2S_Transmit_DMA()
77 (+) At transmission end of half transfer HAL_I2S_TxHalfCpltCallback is executed and user can
78 add his own code by customization of function pointer HAL_I2S_TxHalfCpltCallback
79 (+) At transmission end of transfer HAL_I2S_TxCpltCallback is executed and user can
80 add his own code by customization of function pointer HAL_I2S_TxCpltCallback
81 (+) Receive an amount of data in non blocking mode (DMA) using HAL_I2S_Receive_DMA()
82 (+) At reception end of half transfer HAL_I2S_RxHalfCpltCallback is executed and user can
83 add his own code by customization of function pointer HAL_I2S_RxHalfCpltCallback
84 (+) At reception end of transfer HAL_I2S_RxCpltCallback is executed and user can
85 add his own code by customization of function pointer HAL_I2S_RxCpltCallback
86 (+) In case of transfer Error, HAL_I2S_ErrorCallback() function is executed and user can
87 add his own code by customization of function pointer HAL_I2S_ErrorCallback
88 (+) Pause the DMA Transfer using HAL_I2S_DMAPause()
89 (+) Resume the DMA Transfer using HAL_I2S_DMAResume()
90 (+) Stop the DMA Transfer using HAL_I2S_DMAStop()
92 *** I2S HAL driver macros list ***
93 =============================================
94 [..]
95 Below the list of most used macros in I2S HAL driver.
97 (+) __HAL_I2S_ENABLE: Enable the specified SPI peripheral (in I2S mode)
98 (+) __HAL_I2S_DISABLE: Disable the specified SPI peripheral (in I2S mode)
99 (+) __HAL_I2S_ENABLE_IT : Enable the specified I2S interrupts
100 (+) __HAL_I2S_DISABLE_IT : Disable the specified I2S interrupts
101 (+) __HAL_I2S_GET_FLAG: Check whether the specified I2S flag is set or not
103 [..]
104 (@) You can refer to the I2S HAL driver header file for more useful macros
106 @endverbatim
107 ******************************************************************************
108 * @attention
110 * <h2><center>&copy; COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
112 * Redistribution and use in source and binary forms, with or without modification,
113 * are permitted provided that the following conditions are met:
114 * 1. Redistributions of source code must retain the above copyright notice,
115 * this list of conditions and the following disclaimer.
116 * 2. Redistributions in binary form must reproduce the above copyright notice,
117 * this list of conditions and the following disclaimer in the documentation
118 * and/or other materials provided with the distribution.
119 * 3. Neither the name of STMicroelectronics nor the names of its contributors
120 * may be used to endorse or promote products derived from this software
121 * without specific prior written permission.
123 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
124 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
125 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
126 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
127 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
128 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
129 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
130 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
131 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
132 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
134 ******************************************************************************
137 /* Includes ------------------------------------------------------------------*/
138 #include "stm32f3xx_hal.h"
140 #ifdef HAL_I2S_MODULE_ENABLED
142 #if defined(STM32F302xE) || defined(STM32F303xE) || defined(STM32F398xx) || \
143 defined(STM32F302xC) || defined(STM32F303xC) || defined(STM32F358xx) || \
144 defined(STM32F301x8) || defined(STM32F302x8) || defined(STM32F318xx) || \
145 defined(STM32F373xC) || defined(STM32F378xx)
147 /** @addtogroup STM32F3xx_HAL_Driver
148 * @{
151 /** @defgroup I2S I2S
152 * @brief I2S HAL module driver
153 * @{
156 /* Private typedef -----------------------------------------------------------*/
157 /* Private define ------------------------------------------------------------*/
158 /* Private macro -------------------------------------------------------------*/
159 /* Private variables ---------------------------------------------------------*/
160 /* Private function prototypes -----------------------------------------------*/
161 /** @defgroup I2S_Private_Functions I2S Private Functions
162 * @{
164 static void I2S_DMATxCplt(DMA_HandleTypeDef *hdma);
165 static void I2S_DMATxHalfCplt(DMA_HandleTypeDef *hdma);
166 static void I2S_DMARxCplt(DMA_HandleTypeDef *hdma);
167 static void I2S_DMARxHalfCplt(DMA_HandleTypeDef *hdma);
168 static void I2S_DMAError(DMA_HandleTypeDef *hdma);
169 static void I2S_Transmit_IT(I2S_HandleTypeDef *hi2s);
170 static void I2S_Receive_IT(I2S_HandleTypeDef *hi2s);
171 static HAL_StatusTypeDef I2S_WaitFlagStateUntilTimeout(I2S_HandleTypeDef *hi2s, uint32_t Flag, uint32_t State, uint32_t Timeout);
173 * @}
176 /* Exported functions ---------------------------------------------------------*/
178 /** @defgroup I2S_Exported_Functions I2S Exported Functions
179 * @{
182 /** @defgroup I2S_Exported_Functions_Group1 Initialization and de-initialization functions
183 * @brief Initialization and Configuration functions
185 @verbatim
186 ===============================================================================
187 ##### Initialization and de-initialization functions #####
188 ===============================================================================
189 [..] This subsection provides a set of functions allowing to initialize and
190 de-initialiaze the I2Sx peripheral in simplex mode:
192 (+) User must Implement HAL_I2S_MspInit() function in which he configures
193 all related peripherals resources (CLOCK, GPIO, DMA, IT and NVIC ).
195 (+) Call the function HAL_I2S_Init() to configure the selected device with
196 the selected configuration:
197 (++) Mode
198 (++) Standard
199 (++) Data Format
200 (++) MCLK Output
201 (++) Audio frequency
202 (++) Polarity
203 (++) Full duplex mode
205 (+) Call the function HAL_I2S_DeInit() to restore the default configuration
206 of the selected I2Sx periperal.
207 @endverbatim
208 * @{
212 * @brief Initializes the I2S according to the specified parameters
213 * in the I2S_InitTypeDef and create the associated handle.
214 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
215 * the configuration information for I2S module
216 * @retval HAL status
218 __weak HAL_StatusTypeDef HAL_I2S_Init(I2S_HandleTypeDef *hi2s)
220 /* Prevent unused argument(s) compilation warning */
221 UNUSED(hi2s);
223 /* Note : This function is defined into this file for library reference. */
224 /* Function content is located into file stm32f3xx_hal_i2s_ex.c to */
225 /* handle the possible I2S interfaces defined in STM32F3xx devices */
227 /* Return error status as not implemented here */
228 return HAL_ERROR;
232 * @brief DeInitializes the I2S peripheral
233 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
234 * the configuration information for I2S module
235 * @retval HAL status
237 HAL_StatusTypeDef HAL_I2S_DeInit(I2S_HandleTypeDef *hi2s)
239 /* Check the I2S handle allocation */
240 if(hi2s == NULL)
242 return HAL_ERROR;
245 /* Check the parameters */
246 assert_param(IS_I2S_ALL_INSTANCE(hi2s->Instance));
248 hi2s->State = HAL_I2S_STATE_BUSY;
250 /* DeInit the low level hardware: GPIO, CLOCK, NVIC... */
251 HAL_I2S_MspDeInit(hi2s);
253 hi2s->ErrorCode = HAL_I2S_ERROR_NONE;
254 hi2s->State = HAL_I2S_STATE_RESET;
256 /* Release Lock */
257 __HAL_UNLOCK(hi2s);
259 return HAL_OK;
263 * @brief I2S MSP Init
264 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
265 * the configuration information for I2S module
266 * @retval None
268 __weak void HAL_I2S_MspInit(I2S_HandleTypeDef *hi2s)
270 /* Prevent unused argument(s) compilation warning */
271 UNUSED(hi2s);
273 /* NOTE : This function Should not be modified, when the callback is needed,
274 the HAL_I2S_MspInit could be implemented in the user file
279 * @brief I2S MSP DeInit
280 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
281 * the configuration information for I2S module
282 * @retval None
284 __weak void HAL_I2S_MspDeInit(I2S_HandleTypeDef *hi2s)
286 /* Prevent unused argument(s) compilation warning */
287 UNUSED(hi2s);
289 /* NOTE : This function Should not be modified, when the callback is needed,
290 the HAL_I2S_MspDeInit could be implemented in the user file
295 * @}
298 /** @defgroup I2S_Exported_Functions_Group2 IO operation functions
299 * @brief Data transfers functions
301 @verbatim
302 ===============================================================================
303 ##### IO operation functions #####
304 ===============================================================================
305 [..]
306 This subsection provides a set of functions allowing to manage the I2S data
307 transfers.
309 (#) There are two modes of transfer:
310 (++) Blocking mode : The communication is performed in the polling mode.
311 The status of all data processing is returned by the same function
312 after finishing transfer.
313 (++) No-Blocking mode : The communication is performed using Interrupts
314 or DMA. These functions return the status of the transfer startup.
315 The end of the data processing will be indicated through the
316 dedicated I2S IRQ when using Interrupt mode or the DMA IRQ when
317 using DMA mode.
319 (#) Blocking mode functions are :
320 (++) HAL_I2S_Transmit()
321 (++) HAL_I2S_Receive()
323 (#) No-Blocking mode functions with Interrupt are :
324 (++) HAL_I2S_Transmit_IT()
325 (++) HAL_I2S_Receive_IT()
327 (#) No-Blocking mode functions with DMA are :
328 (++) HAL_I2S_Transmit_DMA()
329 (++) HAL_I2S_Receive_DMA()
331 (#) A set of Transfer Complete Callbacks are provided in non Blocking mode:
332 (++) HAL_I2S_TxCpltCallback()
333 (++) HAL_I2S_RxCpltCallback()
334 (++) HAL_I2S_ErrorCallback()
336 @endverbatim
337 * @{
341 * @brief Transmit an amount of data in blocking mode
342 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
343 * the configuration information for I2S module
344 * @param pData a 16-bit pointer to data buffer.
345 * @param Size number of data sample to be sent:
346 * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S
347 * configuration phase, the Size parameter means the number of 16-bit data length
348 * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected
349 * the Size parameter means the number of 16-bit data length.
350 * @param Timeout Timeout duration
351 * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization
352 * between Master and Slave(example: audio streaming).
353 * @retval HAL status
355 HAL_StatusTypeDef HAL_I2S_Transmit(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size, uint32_t Timeout)
357 if((pData == NULL ) || (Size == 0U))
359 return HAL_ERROR;
362 if(hi2s->State == HAL_I2S_STATE_READY)
364 if(((hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN)) == I2S_DATAFORMAT_24B)||\
365 ((hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN)) == I2S_DATAFORMAT_32B))
367 hi2s->TxXferSize = (Size << 1U);
368 hi2s->TxXferCount = (Size << 1U);
370 else
372 hi2s->TxXferSize = Size;
373 hi2s->TxXferCount = Size;
376 /* Process Locked */
377 __HAL_LOCK(hi2s);
379 hi2s->ErrorCode = HAL_I2S_ERROR_NONE;
380 hi2s->State = HAL_I2S_STATE_BUSY_TX;
382 /* Check if the I2S is already enabled */
383 if((hi2s->Instance->I2SCFGR &SPI_I2SCFGR_I2SE) != SPI_I2SCFGR_I2SE)
385 /* Enable I2S peripheral */
386 __HAL_I2S_ENABLE(hi2s);
389 while(hi2s->TxXferCount > 0U)
391 hi2s->Instance->DR = (*pData++);
392 hi2s->TxXferCount--;
393 /* Wait until TXE flag is set */
394 if (I2S_WaitFlagStateUntilTimeout(hi2s, I2S_FLAG_TXE, RESET, Timeout) != HAL_OK)
396 /* Set the error code and execute error callback*/
397 hi2s->ErrorCode |= HAL_I2S_ERROR_TIMEOUT;
398 HAL_I2S_ErrorCallback(hi2s);
399 return HAL_TIMEOUT;
402 /* Check if an underrun occurs */
403 if(__HAL_I2S_GET_FLAG(hi2s, I2S_FLAG_UDR) == SET)
405 /* Set the I2S State ready */
406 hi2s->State = HAL_I2S_STATE_READY;
408 /* Process Unlocked */
409 __HAL_UNLOCK(hi2s);
411 /* Set the error code and execute error callback*/
412 hi2s->ErrorCode |= HAL_I2S_ERROR_UDR;
413 HAL_I2S_ErrorCallback(hi2s);
415 return HAL_ERROR;
418 hi2s->State = HAL_I2S_STATE_READY;
420 /* Process Unlocked */
421 __HAL_UNLOCK(hi2s);
423 return HAL_OK;
425 else
427 return HAL_BUSY;
432 * @brief Receive an amount of data in blocking mode
433 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
434 * the configuration information for I2S module
435 * @param pData a 16-bit pointer to data buffer.
436 * @param Size number of data sample to be sent:
437 * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S
438 * configuration phase, the Size parameter means the number of 16-bit data length
439 * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected
440 * the Size parameter means the number of 16-bit data length.
441 * @param Timeout Timeout duration
442 * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization
443 * between Master and Slave(example: audio streaming).
444 * @note In I2S Master Receiver mode, just after enabling the peripheral the clock will be generate
445 * in continouse way and as the I2S is not disabled at the end of the I2S transaction.
446 * @retval HAL status
448 HAL_StatusTypeDef HAL_I2S_Receive(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size, uint32_t Timeout)
450 if((pData == NULL ) || (Size == 0U))
452 return HAL_ERROR;
455 if(hi2s->State == HAL_I2S_STATE_READY)
457 if(((hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN)) == I2S_DATAFORMAT_24B)||\
458 ((hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN)) == I2S_DATAFORMAT_32B))
460 hi2s->RxXferSize = (Size << 1U);
461 hi2s->RxXferCount = (Size << 1U);
463 else
465 hi2s->RxXferSize = Size;
466 hi2s->RxXferCount = Size;
468 /* Process Locked */
469 __HAL_LOCK(hi2s);
471 hi2s->ErrorCode = HAL_I2S_ERROR_NONE;
472 hi2s->State = HAL_I2S_STATE_BUSY_RX;
474 /* Check if the I2S is already enabled */
475 if((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SE) != SPI_I2SCFGR_I2SE)
477 /* Enable I2S peripheral */
478 __HAL_I2S_ENABLE(hi2s);
481 /* Check if Master Receiver mode is selected */
482 if((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SCFG) == I2S_MODE_MASTER_RX)
484 /* Clear the Overrun Flag by a read operation on the SPI_DR register followed by a read
485 access to the SPI_SR register. */
486 __HAL_I2S_CLEAR_OVRFLAG(hi2s);
489 /* Receive data */
490 while(hi2s->RxXferCount > 0U)
492 /* Wait until RXNE flag is set */
493 if (I2S_WaitFlagStateUntilTimeout(hi2s, I2S_FLAG_RXNE, RESET, Timeout) != HAL_OK)
495 /* Set the error code and execute error callback*/
496 hi2s->ErrorCode |= HAL_I2S_ERROR_TIMEOUT;
497 HAL_I2S_ErrorCallback(hi2s);
498 return HAL_TIMEOUT;
501 /* Check if an overrun occurs */
502 if(__HAL_I2S_GET_FLAG(hi2s, I2S_FLAG_OVR) == SET)
504 /* Set the I2S State ready */
505 hi2s->State = HAL_I2S_STATE_READY;
507 /* Process Unlocked */
508 __HAL_UNLOCK(hi2s);
510 /* Set the error code and execute error callback*/
511 hi2s->ErrorCode |= HAL_I2S_ERROR_OVR;
512 HAL_I2S_ErrorCallback(hi2s);
514 return HAL_ERROR;
517 (*pData++) = hi2s->Instance->DR;
518 hi2s->RxXferCount--;
521 hi2s->State = HAL_I2S_STATE_READY;
523 /* Process Unlocked */
524 __HAL_UNLOCK(hi2s);
526 return HAL_OK;
528 else
530 return HAL_BUSY;
535 * @brief Transmit an amount of data in non-blocking mode with Interrupt
536 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
537 * the configuration information for I2S module
538 * @param pData a 16-bit pointer to data buffer.
539 * @param Size number of data sample to be sent:
540 * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S
541 * configuration phase, the Size parameter means the number of 16-bit data length
542 * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected
543 * the Size parameter means the number of 16-bit data length.
544 * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization
545 * between Master and Slave(example: audio streaming).
546 * @retval HAL status
548 HAL_StatusTypeDef HAL_I2S_Transmit_IT(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size)
550 if(hi2s->State == HAL_I2S_STATE_READY)
552 if((pData == NULL) || (Size == 0U))
554 return HAL_ERROR;
557 hi2s->pTxBuffPtr = pData;
558 if(((hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN)) == I2S_DATAFORMAT_24B)||\
559 ((hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN)) == I2S_DATAFORMAT_32B))
561 hi2s->TxXferSize = (Size << 1U);
562 hi2s->TxXferCount = (Size << 1U);
564 else
566 hi2s->TxXferSize = Size;
567 hi2s->TxXferCount = Size;
570 /* Process Locked */
571 __HAL_LOCK(hi2s);
573 hi2s->ErrorCode = HAL_I2S_ERROR_NONE;
574 hi2s->State = HAL_I2S_STATE_BUSY_TX;
576 /* Enable TXE and ERR interrupt */
577 __HAL_I2S_ENABLE_IT(hi2s, (I2S_IT_TXE | I2S_IT_ERR));
579 /* Check if the I2S is already enabled */
580 if((hi2s->Instance->I2SCFGR &SPI_I2SCFGR_I2SE) != SPI_I2SCFGR_I2SE)
582 /* Enable I2S peripheral */
583 __HAL_I2S_ENABLE(hi2s);
586 /* Process Unlocked */
587 __HAL_UNLOCK(hi2s);
589 return HAL_OK;
591 else
593 return HAL_BUSY;
598 * @brief Receive an amount of data in non-blocking mode with Interrupt
599 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
600 * the configuration information for I2S module
601 * @param pData a 16-bit pointer to the Receive data buffer.
602 * @param Size number of data sample to be sent:
603 * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S
604 * configuration phase, the Size parameter means the number of 16-bit data length
605 * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected
606 * the Size parameter means the number of 16-bit data length.
607 * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization
608 * between Master and Slave(example: audio streaming).
609 * @note It is recommended to use DMA for the I2S receiver to avoid de-synchronisation
610 * between Master and Slave otherwise the I2S interrupt should be optimized.
611 * @retval HAL status
613 HAL_StatusTypeDef HAL_I2S_Receive_IT(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size)
615 if(hi2s->State == HAL_I2S_STATE_READY)
617 if((pData == NULL) || (Size == 0U))
619 return HAL_ERROR;
622 hi2s->pRxBuffPtr = pData;
623 if(((hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN)) == I2S_DATAFORMAT_24B)||\
624 ((hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN)) == I2S_DATAFORMAT_32B))
626 hi2s->RxXferSize = (Size << 1U);
627 hi2s->RxXferCount = (Size << 1U);
629 else
631 hi2s->RxXferSize = Size;
632 hi2s->RxXferCount = Size;
634 /* Process Locked */
635 __HAL_LOCK(hi2s);
637 hi2s->ErrorCode = HAL_I2S_ERROR_NONE;
638 hi2s->State = HAL_I2S_STATE_BUSY_RX;
640 /* Enable TXE and ERR interrupt */
641 __HAL_I2S_ENABLE_IT(hi2s, (I2S_IT_RXNE | I2S_IT_ERR));
643 /* Check if the I2S is already enabled */
644 if((hi2s->Instance->I2SCFGR &SPI_I2SCFGR_I2SE) != SPI_I2SCFGR_I2SE)
646 /* Enable I2S peripheral */
647 __HAL_I2S_ENABLE(hi2s);
650 /* Process Unlocked */
651 __HAL_UNLOCK(hi2s);
653 return HAL_OK;
655 else
657 return HAL_BUSY;
662 * @brief Transmit an amount of data in non-blocking mode with DMA
663 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
664 * the configuration information for I2S module
665 * @param pData a 16-bit pointer to the Transmit data buffer.
666 * @param Size number of data sample to be sent:
667 * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S
668 * configuration phase, the Size parameter means the number of 16-bit data length
669 * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected
670 * the Size parameter means the number of 16-bit data length.
671 * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization
672 * between Master and Slave(example: audio streaming).
673 * @retval HAL status
675 HAL_StatusTypeDef HAL_I2S_Transmit_DMA(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size)
677 uint32_t *tmp;
679 if((pData == NULL) || (Size == 0U))
681 return HAL_ERROR;
684 if(hi2s->State == HAL_I2S_STATE_READY)
686 hi2s->pTxBuffPtr = pData;
687 if(((hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN)) == I2S_DATAFORMAT_24B)||\
688 ((hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN)) == I2S_DATAFORMAT_32B))
690 hi2s->TxXferSize = (Size << 1U);
691 hi2s->TxXferCount = (Size << 1U);
693 else
695 hi2s->TxXferSize = Size;
696 hi2s->TxXferCount = Size;
699 /* Process Locked */
700 __HAL_LOCK(hi2s);
702 hi2s->ErrorCode = HAL_I2S_ERROR_NONE;
703 hi2s->State = HAL_I2S_STATE_BUSY_TX;
705 /* Set the I2S Tx DMA Half transfer complete callback */
706 hi2s->hdmatx->XferHalfCpltCallback = I2S_DMATxHalfCplt;
708 /* Set the I2S Tx DMA transfer complete callback */
709 hi2s->hdmatx->XferCpltCallback = I2S_DMATxCplt;
711 /* Set the DMA error callback */
712 hi2s->hdmatx->XferErrorCallback = I2S_DMAError;
714 /* Enable the Tx DMA Channel */
715 tmp = (uint32_t*)&pData;
716 HAL_DMA_Start_IT(hi2s->hdmatx, *(uint32_t*)tmp, (uint32_t)&hi2s->Instance->DR, hi2s->TxXferSize);
718 /* Check if the I2S is already enabled */
719 if((hi2s->Instance->I2SCFGR &SPI_I2SCFGR_I2SE) != SPI_I2SCFGR_I2SE)
721 /* Enable I2S peripheral */
722 __HAL_I2S_ENABLE(hi2s);
725 /* Enable Tx DMA Request */
726 hi2s->Instance->CR2 |= SPI_CR2_TXDMAEN;
728 /* Process Unlocked */
729 __HAL_UNLOCK(hi2s);
731 return HAL_OK;
733 else
735 return HAL_BUSY;
740 * @brief Receive an amount of data in non-blocking mode with DMA
741 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
742 * the configuration information for I2S module
743 * @param pData a 16-bit pointer to the Receive data buffer.
744 * @param Size number of data sample to be sent:
745 * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S
746 * configuration phase, the Size parameter means the number of 16-bit data length
747 * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected
748 * the Size parameter means the number of 16-bit data length.
749 * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization
750 * between Master and Slave(example: audio streaming).
751 * @retval HAL status
753 HAL_StatusTypeDef HAL_I2S_Receive_DMA(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size)
755 uint32_t *tmp;
757 if((pData == NULL) || (Size == 0U))
759 return HAL_ERROR;
762 if(hi2s->State == HAL_I2S_STATE_READY)
764 hi2s->pRxBuffPtr = pData;
765 if(((hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN)) == I2S_DATAFORMAT_24B)||\
766 ((hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN)) == I2S_DATAFORMAT_32B))
768 hi2s->RxXferSize = (Size << 1U);
769 hi2s->RxXferCount = (Size << 1U);
771 else
773 hi2s->RxXferSize = Size;
774 hi2s->RxXferCount = Size;
776 /* Process Locked */
777 __HAL_LOCK(hi2s);
779 hi2s->ErrorCode = HAL_I2S_ERROR_NONE;
780 hi2s->State = HAL_I2S_STATE_BUSY_RX;
782 /* Set the I2S Rx DMA Half transfer complete callback */
783 hi2s->hdmarx->XferHalfCpltCallback = I2S_DMARxHalfCplt;
785 /* Set the I2S Rx DMA transfer complete callback */
786 hi2s->hdmarx->XferCpltCallback = I2S_DMARxCplt;
788 /* Set the DMA error callback */
789 hi2s->hdmarx->XferErrorCallback = I2S_DMAError;
791 /* Check if Master Receiver mode is selected */
792 if((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SCFG) == I2S_MODE_MASTER_RX)
794 /* Clear the Overrun Flag by a read operation to the SPI_DR register followed by a read
795 access to the SPI_SR register. */
796 __HAL_I2S_CLEAR_OVRFLAG(hi2s);
799 /* Enable the Rx DMA Channel */
800 tmp = (uint32_t*)&pData;
801 HAL_DMA_Start_IT(hi2s->hdmarx, (uint32_t)&hi2s->Instance->DR, *(uint32_t*)tmp, hi2s->RxXferSize);
803 /* Check if the I2S is already enabled */
804 if((hi2s->Instance->I2SCFGR &SPI_I2SCFGR_I2SE) != SPI_I2SCFGR_I2SE)
806 /* Enable I2S peripheral */
807 __HAL_I2S_ENABLE(hi2s);
810 /* Enable Rx DMA Request */
811 hi2s->Instance->CR2 |= SPI_CR2_RXDMAEN;
813 /* Process Unlocked */
814 __HAL_UNLOCK(hi2s);
816 return HAL_OK;
818 else
820 return HAL_BUSY;
825 * @brief Pauses the audio stream playing from the Media.
826 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
827 * the configuration information for I2S module
828 * @retval HAL status
830 __weak HAL_StatusTypeDef HAL_I2S_DMAPause(I2S_HandleTypeDef *hi2s)
832 /* Process Locked */
833 __HAL_LOCK(hi2s);
835 if(hi2s->State == HAL_I2S_STATE_BUSY_TX)
837 /* Disable the I2S DMA Tx request */
838 hi2s->Instance->CR2 &= (uint32_t)(~SPI_CR2_TXDMAEN);
840 else if(hi2s->State == HAL_I2S_STATE_BUSY_RX)
842 /* Disable the I2S DMA Rx request */
843 hi2s->Instance->CR2 &= (uint32_t)(~SPI_CR2_RXDMAEN);
846 /* Process Unlocked */
847 __HAL_UNLOCK(hi2s);
849 return HAL_OK;
853 * @brief Resumes the audio stream playing from the Media.
854 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
855 * the configuration information for I2S module
856 * @retval HAL status
858 __weak HAL_StatusTypeDef HAL_I2S_DMAResume(I2S_HandleTypeDef *hi2s)
860 /* Process Locked */
861 __HAL_LOCK(hi2s);
863 if(hi2s->State == HAL_I2S_STATE_BUSY_TX)
865 /* Enable the I2S DMA Tx request */
866 hi2s->Instance->CR2 |= SPI_CR2_TXDMAEN;
868 else if(hi2s->State == HAL_I2S_STATE_BUSY_RX)
870 /* Enable the I2S DMA Rx request */
871 hi2s->Instance->CR2 |= SPI_CR2_RXDMAEN;
874 /* If the I2S peripheral is still not enabled, enable it */
875 if ((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SE) == 0U)
877 /* Enable I2S peripheral */
878 __HAL_I2S_ENABLE(hi2s);
881 /* Process Unlocked */
882 __HAL_UNLOCK(hi2s);
884 return HAL_OK;
888 * @brief Resumes the audio stream playing from the Media.
889 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
890 * the configuration information for I2S module
891 * @retval HAL status
893 __weak HAL_StatusTypeDef HAL_I2S_DMAStop(I2S_HandleTypeDef *hi2s)
895 /* Process Locked */
896 __HAL_LOCK(hi2s);
898 /* Disable the I2S Tx/Rx DMA requests */
899 hi2s->Instance->CR2 &= (uint32_t)(~SPI_CR2_TXDMAEN);
900 hi2s->Instance->CR2 &= (uint32_t)(~SPI_CR2_RXDMAEN);
902 /* Abort the I2S DMA tx channel */
903 if(hi2s->hdmatx != NULL)
905 /* Disable the I2S DMA channel */
906 __HAL_DMA_DISABLE(hi2s->hdmatx);
907 HAL_DMA_Abort(hi2s->hdmatx);
909 /* Abort the I2S DMA rx channel */
910 if(hi2s->hdmarx != NULL)
912 /* Disable the I2S DMA channel */
913 __HAL_DMA_DISABLE(hi2s->hdmarx);
914 HAL_DMA_Abort(hi2s->hdmarx);
917 /* Disable I2S peripheral */
918 __HAL_I2S_DISABLE(hi2s);
920 hi2s->State = HAL_I2S_STATE_READY;
922 /* Process Unlocked */
923 __HAL_UNLOCK(hi2s);
925 return HAL_OK;
929 * @brief This function handles I2S interrupt request.
930 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
931 * the configuration information for I2S module
932 * @retval None
934 void HAL_I2S_IRQHandler(I2S_HandleTypeDef *hi2s)
936 __IO uint32_t i2ssr = hi2s->Instance->SR;
938 if(hi2s->State == HAL_I2S_STATE_BUSY_RX)
940 /* I2S in mode Receiver ----------------------------------------------------*/
941 if(((i2ssr & I2S_FLAG_RXNE) == I2S_FLAG_RXNE) && (__HAL_I2S_GET_IT_SOURCE(hi2s, I2S_IT_RXNE) != RESET))
943 I2S_Receive_IT(hi2s);
946 /* I2S Overrun error interrupt occured -------------------------------------*/
947 if(((i2ssr & I2S_FLAG_OVR) == I2S_FLAG_OVR) && (__HAL_I2S_GET_IT_SOURCE(hi2s, I2S_IT_ERR) != RESET))
949 /* Disable RXNE and ERR interrupt */
950 __HAL_I2S_DISABLE_IT(hi2s, (I2S_IT_RXNE | I2S_IT_ERR));
952 /* Set the I2S State ready */
953 hi2s->State = HAL_I2S_STATE_READY;
955 /* Set the error code and execute error callback*/
956 hi2s->ErrorCode |= HAL_I2S_ERROR_OVR;
957 HAL_I2S_ErrorCallback(hi2s);
960 else if(hi2s->State == HAL_I2S_STATE_BUSY_TX)
962 /* I2S in mode Tramitter ---------------------------------------------------*/
963 if(((i2ssr & I2S_FLAG_TXE) == I2S_FLAG_TXE) && (__HAL_I2S_GET_IT_SOURCE(hi2s, I2S_IT_TXE) != RESET))
965 I2S_Transmit_IT(hi2s);
968 /* I2S Underrun error interrupt occured ------------------------------------*/
969 if(((i2ssr & I2S_FLAG_UDR) == I2S_FLAG_UDR) && (__HAL_I2S_GET_IT_SOURCE(hi2s, I2S_IT_ERR) != RESET))
971 /* Disable TXE and ERR interrupt */
972 __HAL_I2S_DISABLE_IT(hi2s, (I2S_IT_TXE | I2S_IT_ERR));
974 /* Set the I2S State ready */
975 hi2s->State = HAL_I2S_STATE_READY;
977 /* Set the error code and execute error callback*/
978 hi2s->ErrorCode |= HAL_I2S_ERROR_UDR;
979 HAL_I2S_ErrorCallback(hi2s);
985 * @}
989 * @}
994 /** @addtogroup I2S_Exported_Functions I2S Exported Functions
995 * @{
998 /** @addtogroup I2S_Exported_Functions_Group2 IO operation functions
999 * @{
1002 * @brief Tx Transfer Half completed callbacks
1003 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1004 * the configuration information for I2S module
1005 * @retval None
1007 __weak void HAL_I2S_TxHalfCpltCallback(I2S_HandleTypeDef *hi2s)
1009 /* Prevent unused argument(s) compilation warning */
1010 UNUSED(hi2s);
1012 /* NOTE : This function Should not be modified, when the callback is needed,
1013 the HAL_I2S_TxHalfCpltCallback could be implemented in the user file
1018 * @brief Tx Transfer completed callbacks
1019 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1020 * the configuration information for I2S module
1021 * @retval None
1023 __weak void HAL_I2S_TxCpltCallback(I2S_HandleTypeDef *hi2s)
1025 /* Prevent unused argument(s) compilation warning */
1026 UNUSED(hi2s);
1028 /* NOTE : This function Should not be modified, when the callback is needed,
1029 the HAL_I2S_TxCpltCallback could be implemented in the user file
1034 * @brief Rx Transfer half completed callbacks
1035 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1036 * the configuration information for I2S module
1037 * @retval None
1039 __weak void HAL_I2S_RxHalfCpltCallback(I2S_HandleTypeDef *hi2s)
1041 /* Prevent unused argument(s) compilation warning */
1042 UNUSED(hi2s);
1044 /* NOTE : This function Should not be modified, when the callback is needed,
1045 the HAL_I2S_RxCpltCallback could be implemented in the user file
1050 * @brief Rx Transfer completed callbacks
1051 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1052 * the configuration information for I2S module
1053 * @retval None
1055 __weak void HAL_I2S_RxCpltCallback(I2S_HandleTypeDef *hi2s)
1057 /* Prevent unused argument(s) compilation warning */
1058 UNUSED(hi2s);
1060 /* NOTE : This function Should not be modified, when the callback is needed,
1061 the HAL_I2S_RxCpltCallback could be implemented in the user file
1066 * @brief I2S error callbacks
1067 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1068 * the configuration information for I2S module
1069 * @retval None
1071 __weak void HAL_I2S_ErrorCallback(I2S_HandleTypeDef *hi2s)
1073 /* Prevent unused argument(s) compilation warning */
1074 UNUSED(hi2s);
1076 /* NOTE : This function Should not be modified, when the callback is needed,
1077 the HAL_I2S_ErrorCallback could be implemented in the user file
1082 * @}
1085 /** @defgroup I2S_Exported_Functions_Group3 Peripheral State and Errors functions
1086 * @brief Peripheral State functions
1088 @verbatim
1089 ===============================================================================
1090 ##### Peripheral State and Errors functions #####
1091 ===============================================================================
1092 [..]
1093 This subsection permits to get in run-time the status of the peripheral
1094 and the data flow.
1096 @endverbatim
1097 * @{
1101 * @brief Return the I2S state
1102 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1103 * the configuration information for I2S module
1104 * @retval HAL state
1106 HAL_I2S_StateTypeDef HAL_I2S_GetState(I2S_HandleTypeDef *hi2s)
1108 return hi2s->State;
1112 * @brief Return the I2S error code
1113 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1114 * the configuration information for I2S module
1115 * @retval I2S Error Code
1117 uint32_t HAL_I2S_GetError(I2S_HandleTypeDef *hi2s)
1119 return hi2s->ErrorCode;
1122 * @}
1126 * @}
1129 /** @addtogroup I2S_Private_Functions I2S Private Functions
1130 * @{
1133 * @brief DMA I2S transmit process complete callback
1134 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
1135 * the configuration information for the specified DMA module.
1136 * @retval None
1138 static void I2S_DMATxCplt(DMA_HandleTypeDef *hdma)
1140 I2S_HandleTypeDef* hi2s = ( I2S_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent;
1142 if((hdma->Instance->CCR & DMA_CCR_CIRC) == 0U)
1144 /* Disable Tx DMA Request */
1145 hi2s->Instance->CR2 &= (uint32_t)(~SPI_CR2_TXDMAEN);
1147 hi2s->TxXferCount = 0U;
1148 hi2s->State = HAL_I2S_STATE_READY;
1150 HAL_I2S_TxCpltCallback(hi2s);
1154 * @brief DMA I2S transmit process half complete callback
1155 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
1156 * the configuration information for the specified DMA module.
1157 * @retval None
1159 static void I2S_DMATxHalfCplt(DMA_HandleTypeDef *hdma)
1161 I2S_HandleTypeDef* hi2s = (I2S_HandleTypeDef*)((DMA_HandleTypeDef*)hdma)->Parent;
1163 HAL_I2S_TxHalfCpltCallback(hi2s);
1167 * @brief DMA I2S receive process complete callback
1168 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
1169 * the configuration information for the specified DMA module.
1170 * @retval None
1172 static void I2S_DMARxCplt(DMA_HandleTypeDef *hdma)
1174 I2S_HandleTypeDef* hi2s = ( I2S_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent;
1176 if((hdma->Instance->CCR & DMA_CCR_CIRC) == 0U)
1178 /* Disable Rx DMA Request */
1179 hi2s->Instance->CR2 &= (uint32_t)(~SPI_CR2_RXDMAEN);
1180 hi2s->RxXferCount = 0U;
1181 hi2s->State = HAL_I2S_STATE_READY;
1183 HAL_I2S_RxCpltCallback(hi2s);
1187 * @brief DMA I2S receive process half complete callback
1188 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
1189 * the configuration information for the specified DMA module.
1190 * @retval None
1192 static void I2S_DMARxHalfCplt(DMA_HandleTypeDef *hdma)
1194 I2S_HandleTypeDef* hi2s = (I2S_HandleTypeDef*)((DMA_HandleTypeDef*)hdma)->Parent;
1196 HAL_I2S_RxHalfCpltCallback(hi2s);
1200 * @brief DMA I2S communication error callback
1201 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
1202 * the configuration information for the specified DMA module.
1203 * @retval None
1205 static void I2S_DMAError(DMA_HandleTypeDef *hdma)
1207 I2S_HandleTypeDef* hi2s = ( I2S_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent;
1209 /* Disable Rx and Tx DMA Request */
1210 hi2s->Instance->CR2 &= (uint32_t)(~(SPI_CR2_RXDMAEN | SPI_CR2_TXDMAEN));
1211 hi2s->TxXferCount = 0U;
1212 hi2s->RxXferCount = 0U;
1214 hi2s->State= HAL_I2S_STATE_READY;
1216 /* Set the error code and execute error callback*/
1217 hi2s->ErrorCode |= HAL_I2S_ERROR_DMA;
1218 HAL_I2S_ErrorCallback(hi2s);
1222 * @brief Transmit an amount of data in non-blocking mode with Interrupt
1223 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1224 * the configuration information for I2S module
1225 * @retval None
1227 static void I2S_Transmit_IT(I2S_HandleTypeDef *hi2s)
1229 /* Transmit data */
1230 hi2s->Instance->DR = (*hi2s->pTxBuffPtr++);
1231 hi2s->TxXferCount--;
1233 if(hi2s->TxXferCount == 0U)
1235 /* Disable TXE and ERR interrupt */
1236 __HAL_I2S_DISABLE_IT(hi2s, (I2S_IT_TXE | I2S_IT_ERR));
1238 hi2s->State = HAL_I2S_STATE_READY;
1239 HAL_I2S_TxCpltCallback(hi2s);
1244 * @brief Receive an amount of data in non-blocking mode with Interrupt
1245 * @param hi2s: I2S handle
1246 * @retval None
1248 static void I2S_Receive_IT(I2S_HandleTypeDef *hi2s)
1250 /* Receive data */
1251 (*hi2s->pRxBuffPtr++) = hi2s->Instance->DR;
1252 hi2s->RxXferCount--;
1254 if(hi2s->RxXferCount == 0U)
1256 /* Disable RXNE and ERR interrupt */
1257 __HAL_I2S_DISABLE_IT(hi2s, (I2S_IT_RXNE | I2S_IT_ERR));
1259 hi2s->State = HAL_I2S_STATE_READY;
1260 HAL_I2S_RxCpltCallback(hi2s);
1265 * @brief This function handles I2S Communication Timeout.
1266 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1267 * the configuration information for I2S module
1268 * @param Flag Flag checked
1269 * @param State Value of the flag expected
1270 * @param Timeout Duration of the timeout
1271 * @retval HAL status
1273 static HAL_StatusTypeDef I2S_WaitFlagStateUntilTimeout(I2S_HandleTypeDef *hi2s, uint32_t Flag, uint32_t State, uint32_t Timeout)
1275 uint32_t tickstart = HAL_GetTick();
1277 /* Wait until flag is set */
1278 if(State == RESET)
1280 while(__HAL_I2S_GET_FLAG(hi2s, Flag) == RESET)
1282 if(Timeout != HAL_MAX_DELAY)
1284 if((Timeout == 0U) || ((HAL_GetTick() - tickstart) > Timeout))
1286 /* Set the I2S State ready */
1287 hi2s->State= HAL_I2S_STATE_READY;
1289 /* Process Unlocked */
1290 __HAL_UNLOCK(hi2s);
1292 return HAL_TIMEOUT;
1297 else
1299 while(__HAL_I2S_GET_FLAG(hi2s, Flag) != RESET)
1301 if(Timeout != HAL_MAX_DELAY)
1303 if((Timeout == 0U) || ((HAL_GetTick() - tickstart) > Timeout))
1305 /* Set the I2S State ready */
1306 hi2s->State= HAL_I2S_STATE_READY;
1308 /* Process Unlocked */
1309 __HAL_UNLOCK(hi2s);
1311 return HAL_TIMEOUT;
1316 return HAL_OK;
1320 * @}
1324 * @}
1328 * @}
1330 #endif /* STM32F302xE || STM32F303xE || STM32F398xx || */
1331 /* STM32F302xC || STM32F303xC || STM32F358xx || */
1332 /* STM32F301x8 || STM32F302x8 || STM32F318xx || */
1333 /* STM32F373xC || STM32F378xx */
1335 #endif /* HAL_I2S_MODULE_ENABLED */
1337 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/