2 ******************************************************************************
3 * @file stm32f1xx_hal_i2s.c
4 * @author MCD Application Team
7 * @brief I2S HAL module driver.
8 * This file provides firmware functions to manage the following
9 * functionalities of the Integrated Interchip Sound (I2S) peripheral:
10 * + Initialization and de-initialization functions
11 * + IO operation functions
12 * + Peripheral State and Errors functions
14 ===============================================================================
15 ##### How to use this driver #####
16 ===============================================================================
18 The I2S HAL driver can be used as follow:
20 (#) Declare a I2S_HandleTypeDef handle structure.
21 (#) Initialize the I2S low level resources by implement the HAL_I2S_MspInit() API:
22 (##) Enable the SPIx interface clock.
23 (##) I2S pins configuration:
24 (+++) Enable the clock for the I2S GPIOs.
25 (+++) Configure these I2S pins as alternate function.
26 (##) NVIC configuration if you need to use interrupt process (HAL_I2S_Transmit_IT()
27 and HAL_I2S_Receive_IT() APIs).
28 (+++) Configure the I2Sx interrupt priority.
29 (+++) Enable the NVIC I2S IRQ handle.
30 (##) DMA Configuration if you need to use DMA process (HAL_I2S_Transmit_DMA()
31 and HAL_I2S_Receive_DMA() APIs:
32 (+++) Declare a DMA handle structure for the Tx/Rx Channel.
33 (+++) Enable the DMAx interface clock.
34 (+++) Configure the declared DMA handle structure with the required Tx/Rx parameters.
35 (+++) Configure the DMA Tx/Rx Channel.
36 (+++) Associate the initialized DMA handle to the I2S DMA Tx/Rx handle.
37 (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on the
40 (#) Program the Mode, Standard, Data Format, MCLK Output, Audio frequency and Polarity
41 using HAL_I2S_Init() function.
43 -@- The specific I2S interrupts (Transmission complete interrupt,
44 RXNE interrupt and Error Interrupts) will be managed using the macros
45 __HAL_I2S_ENABLE_IT() and __HAL_I2S_DISABLE_IT() inside the transmit and receive process.
46 -@- The I2SxCLK source is the system clock (provided by the HSI, the HSE or the PLL, and sourcing the AHB clock).
47 For connectivity line devices, the I2SxCLK source can be either SYSCLK or the PLL3 VCO (2 x PLL3CLK) clock
48 in order to achieve the maximum accuracy.
49 -@- Make sure that either:
50 (+@) External clock source is configured after setting correctly
51 the define constant HSE_VALUE in the stm32f1xx_hal_conf.h file.
53 (#) Three operation modes are available within this driver :
55 *** Polling mode IO operation ***
56 =================================
58 (+) Send an amount of data in blocking mode using HAL_I2S_Transmit()
59 (+) Receive an amount of data in blocking mode using HAL_I2S_Receive()
61 *** Interrupt mode IO operation ***
62 ===================================
64 (+) Send an amount of data in non blocking mode using HAL_I2S_Transmit_IT()
65 (+) At transmission end of half transfer HAL_I2S_TxHalfCpltCallback is executed and user can
66 add his own code by customization of function pointer HAL_I2S_TxHalfCpltCallback
67 (+) At transmission end of transfer HAL_I2S_TxCpltCallback is executed and user can
68 add his own code by customization of function pointer HAL_I2S_TxCpltCallback
69 (+) Receive an amount of data in non blocking mode using HAL_I2S_Receive_IT()
70 (+) At reception end of half transfer HAL_I2S_RxHalfCpltCallback is executed and user can
71 add his own code by customization of function pointer HAL_I2S_RxHalfCpltCallback
72 (+) At reception end of transfer HAL_I2S_RxCpltCallback is executed and user can
73 add his own code by customization of function pointer HAL_I2S_RxCpltCallback
74 (+) In case of transfer Error, HAL_I2S_ErrorCallback() function is executed and user can
75 add his own code by customization of function pointer HAL_I2S_ErrorCallback
77 *** DMA mode IO operation ***
78 ==============================
80 (+) Send an amount of data in non blocking mode (DMA) using HAL_I2S_Transmit_DMA()
81 (+) At transmission end of half transfer HAL_I2S_TxHalfCpltCallback is executed and user can
82 add his own code by customization of function pointer HAL_I2S_TxHalfCpltCallback
83 (+) At transmission end of transfer HAL_I2S_TxCpltCallback is executed and user can
84 add his own code by customization of function pointer HAL_I2S_TxCpltCallback
85 (+) Receive an amount of data in non blocking mode (DMA) using HAL_I2S_Receive_DMA()
86 (+) At reception end of half transfer HAL_I2S_RxHalfCpltCallback is executed and user can
87 add his own code by customization of function pointer HAL_I2S_RxHalfCpltCallback
88 (+) At reception end of transfer HAL_I2S_RxCpltCallback is executed and user can
89 add his own code by customization of function pointer HAL_I2S_RxCpltCallback
90 (+) In case of transfer Error, HAL_I2S_ErrorCallback() function is executed and user can
91 add his own code by customization of function pointer HAL_I2S_ErrorCallback
92 (+) Pause the DMA Transfer using HAL_I2S_DMAPause()
93 (+) Resume the DMA Transfer using HAL_I2S_DMAResume()
94 (+) Stop the DMA Transfer using HAL_I2S_DMAStop()
96 *** I2S HAL driver macros list ***
97 =============================================
99 Below the list of most used macros in I2S HAL driver.
101 (+) __HAL_I2S_ENABLE: Enable the specified SPI peripheral (in I2S mode)
102 (+) __HAL_I2S_DISABLE: Disable the specified SPI peripheral (in I2S mode)
103 (+) __HAL_I2S_ENABLE_IT : Enable the specified I2S interrupts
104 (+) __HAL_I2S_DISABLE_IT : Disable the specified I2S interrupts
105 (+) __HAL_I2S_GET_FLAG: Check whether the specified I2S flag is set or not
108 (@) You can refer to the I2S HAL driver header file for more useful macros
111 *** I2C Workarounds linked to Silicon Limitation ***
112 ====================================================
114 (@) Only the 16-bit mode with no data extension can be used when the I2S
115 is in Master and used the PCM long synchronization mode.
119 ******************************************************************************
122 * <h2><center>© COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
124 * Redistribution and use in source and binary forms, with or without modification,
125 * are permitted provided that the following conditions are met:
126 * 1. Redistributions of source code must retain the above copyright notice,
127 * this list of conditions and the following disclaimer.
128 * 2. Redistributions in binary form must reproduce the above copyright notice,
129 * this list of conditions and the following disclaimer in the documentation
130 * and/or other materials provided with the distribution.
131 * 3. Neither the name of STMicroelectronics nor the names of its contributors
132 * may be used to endorse or promote products derived from this software
133 * without specific prior written permission.
135 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
136 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
137 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
138 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
139 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
140 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
141 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
142 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
143 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
144 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
146 ******************************************************************************
149 /* Includes ------------------------------------------------------------------*/
150 #include "stm32f1xx_hal.h"
152 /** @addtogroup STM32F1xx_HAL_Driver
156 #ifdef HAL_I2S_MODULE_ENABLED
157 #if defined(STM32F103xE) || defined(STM32F103xG) || defined(STM32F105xC) || defined(STM32F107xC)
159 /** @defgroup I2S I2S
160 * @brief I2S HAL module driver
164 /* Private typedef -----------------------------------------------------------*/
165 /* Private define ------------------------------------------------------------*/
166 /* Private macro -------------------------------------------------------------*/
167 /* Private variables ---------------------------------------------------------*/
168 /* Private function prototypes -----------------------------------------------*/
169 /** @addtogroup I2S_Private_Functions I2S Private Functions
172 static void I2S_DMATxCplt(DMA_HandleTypeDef
*hdma
);
173 static void I2S_DMATxHalfCplt(DMA_HandleTypeDef
*hdma
);
174 static void I2S_DMARxCplt(DMA_HandleTypeDef
*hdma
);
175 static void I2S_DMARxHalfCplt(DMA_HandleTypeDef
*hdma
);
176 static void I2S_DMAError(DMA_HandleTypeDef
*hdma
);
177 static void I2S_Transmit_IT(I2S_HandleTypeDef
*hi2s
);
178 static void I2S_Receive_IT(I2S_HandleTypeDef
*hi2s
);
179 static void I2S_IRQHandler(I2S_HandleTypeDef
*hi2s
);
180 static HAL_StatusTypeDef
I2S_WaitFlagStateUntilTimeout(I2S_HandleTypeDef
*hi2s
, uint32_t Flag
, uint32_t State
,
186 /* Exported functions ---------------------------------------------------------*/
187 /** @defgroup I2S_Exported_Functions I2S Exported Functions
191 /** @defgroup I2S_Exported_Functions_Group1 Initialization and de-initialization functions
192 * @brief Initialization and Configuration functions
195 ===============================================================================
196 ##### Initialization and de-initialization functions #####
197 ===============================================================================
198 [..] This subsection provides a set of functions allowing to initialize and
199 de-initialize the I2Sx peripheral in simplex mode:
201 (+) User must Implement HAL_I2S_MspInit() function in which he configures
202 all related peripherals resources (CLOCK, GPIO, DMA, IT and NVIC ).
204 (+) Call the function HAL_I2S_Init() to configure the selected device with
205 the selected configuration:
213 (+) Call the function HAL_I2S_DeInit() to restore the default configuration
214 of the selected I2Sx peripheral.
220 * @brief Initializes the I2S according to the specified parameters
221 * in the I2S_InitTypeDef and create the associated handle.
222 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
223 * the configuration information for I2S module
226 HAL_StatusTypeDef
HAL_I2S_Init(I2S_HandleTypeDef
*hi2s
)
228 uint32_t tmpreg
= 0U, i2sdiv
= 2U, i2sodd
= 0U, packetlength
= 16U;
229 uint32_t tmp
= 0U, i2sclk
= 0U;
231 /* Check the I2S handle allocation */
237 /* Check the I2S parameters */
238 assert_param(IS_I2S_ALL_INSTANCE(hi2s
->Instance
));
239 assert_param(IS_I2S_MODE(hi2s
->Init
.Mode
));
240 assert_param(IS_I2S_STANDARD(hi2s
->Init
.Standard
));
241 assert_param(IS_I2S_DATA_FORMAT(hi2s
->Init
.DataFormat
));
242 assert_param(IS_I2S_MCLK_OUTPUT(hi2s
->Init
.MCLKOutput
));
243 assert_param(IS_I2S_AUDIO_FREQ(hi2s
->Init
.AudioFreq
));
244 assert_param(IS_I2S_CPOL(hi2s
->Init
.CPOL
));
246 hi2s
->State
= HAL_I2S_STATE_BUSY
;
248 /* Initialize Default I2S IrqHandler ISR */
249 hi2s
->IrqHandlerISR
= I2S_IRQHandler
;
251 /* Init the low level hardware : GPIO, CLOCK, CORTEX...etc */
252 HAL_I2S_MspInit(hi2s
);
254 /*----------------------- SPIx I2SCFGR & I2SPR Configuration ---------------*/
255 /* Clear I2SMOD, I2SE, I2SCFG, PCMSYNC, I2SSTD, CKPOL, DATLEN and CHLEN bits */
256 CLEAR_BIT(hi2s
->Instance
->I2SCFGR
,(SPI_I2SCFGR_CHLEN
| SPI_I2SCFGR_DATLEN
| SPI_I2SCFGR_CKPOL
| \
257 SPI_I2SCFGR_I2SSTD
| SPI_I2SCFGR_PCMSYNC
| SPI_I2SCFGR_I2SCFG
| \
258 SPI_I2SCFGR_I2SE
| SPI_I2SCFGR_I2SMOD
));
259 hi2s
->Instance
->I2SPR
= 0x0002U
;
261 /* Get the I2SCFGR register value */
262 tmpreg
= hi2s
->Instance
->I2SCFGR
;
264 /* If the default frequency value has to be written, reinitialize i2sdiv and i2sodd */
265 /* If the requested audio frequency is not the default, compute the prescaler */
266 if(hi2s
->Init
.AudioFreq
!= I2S_AUDIOFREQ_DEFAULT
)
268 /* Check the frame length (For the Prescaler computing) *******************/
269 /* Set I2S Packet Length value*/
270 if(hi2s
->Init
.DataFormat
!= I2S_DATAFORMAT_16B
)
272 /* Packet length is 32 bits */
277 /* Packet length is 16 bits */
282 if(hi2s
->Init
.Standard
<= I2S_STANDARD_LSB
)
284 /* In I2S standard packet lenght is multiplied by 2 */
285 packetlength
= packetlength
* 2U;
288 if(hi2s
->Instance
== SPI2
)
290 /* Get the source clock value: based on SPI2 Instance */
291 i2sclk
= HAL_RCCEx_GetPeriphCLKFreq(RCC_PERIPHCLK_I2S2
);
293 else if(hi2s
->Instance
== SPI3
)
295 /* Get the source clock value: based on SPI3 Instance */
296 i2sclk
= HAL_RCCEx_GetPeriphCLKFreq(RCC_PERIPHCLK_I2S3
);
300 /* Get the source clock value: based on System Clock value */
301 i2sclk
= HAL_RCC_GetSysClockFreq();
304 /* Compute the Real divider depending on the MCLK output state, with a floating point */
305 if(hi2s
->Init
.MCLKOutput
== I2S_MCLKOUTPUT_ENABLE
)
307 /* MCLK output is enabled */
308 if (hi2s
->Init
.DataFormat
!= I2S_DATAFORMAT_16B
)
310 tmp
= (uint32_t)(((((i2sclk
/ (packetlength
*4)) * 10) / hi2s
->Init
.AudioFreq
)) + 5);
314 tmp
= (uint32_t)(((((i2sclk
/ (packetlength
*8)) * 10) / hi2s
->Init
.AudioFreq
)) + 5);
319 /* MCLK output is disabled */
320 tmp
= (uint32_t)(((((i2sclk
/ packetlength
) *10 ) / hi2s
->Init
.AudioFreq
)) + 5);
323 /* Remove the flatting point */
326 /* Check the parity of the divider */
327 i2sodd
= (uint16_t)(tmp
& (uint16_t)1U);
329 /* Compute the i2sdiv prescaler */
330 i2sdiv
= (uint16_t)((tmp
- i2sodd
) / 2U);
332 /* Get the Mask for the Odd bit (SPI_I2SPR[8]) register */
333 i2sodd
= (uint32_t) (i2sodd
<< 8U);
336 /* Test if the divider is 1 or 0 or greater than 0xFF */
337 if((i2sdiv
< 2U) || (i2sdiv
> 0xFFU
))
339 /* Set the default values */
343 /* Set the error code and execute error callback*/
344 SET_BIT(hi2s
->ErrorCode
, HAL_I2S_ERROR_PRESCALER
);
345 HAL_I2S_ErrorCallback(hi2s
);
349 /* Write to SPIx I2SPR register the computed value */
350 hi2s
->Instance
->I2SPR
= (uint32_t)((uint32_t)i2sdiv
| (uint32_t)(i2sodd
| (uint32_t)hi2s
->Init
.MCLKOutput
));
352 /* Configure the I2S with the I2S_InitStruct values */
353 tmpreg
|= (uint16_t)((uint16_t)SPI_I2SCFGR_I2SMOD
| (uint16_t)(hi2s
->Init
.Mode
| \
354 (uint16_t)(hi2s
->Init
.Standard
| (uint16_t)(hi2s
->Init
.DataFormat
| \
355 (uint16_t)hi2s
->Init
.CPOL
))));
356 /* Write to SPIx I2SCFGR */
357 WRITE_REG(hi2s
->Instance
->I2SCFGR
,tmpreg
);
358 hi2s
->ErrorCode
= HAL_I2S_ERROR_NONE
;
359 hi2s
->State
= HAL_I2S_STATE_READY
;
365 * @brief DeInitializes the I2S peripheral
366 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
367 * the configuration information for I2S module
370 HAL_StatusTypeDef
HAL_I2S_DeInit(I2S_HandleTypeDef
*hi2s
)
372 /* Check the I2S handle allocation */
378 hi2s
->State
= HAL_I2S_STATE_BUSY
;
380 /* DeInit the low level hardware: GPIO, CLOCK, NVIC... */
381 HAL_I2S_MspDeInit(hi2s
);
383 hi2s
->ErrorCode
= HAL_I2S_ERROR_NONE
;
384 hi2s
->State
= HAL_I2S_STATE_RESET
;
393 * @brief I2S MSP Init
394 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
395 * the configuration information for I2S module
398 __weak
void HAL_I2S_MspInit(I2S_HandleTypeDef
*hi2s
)
400 /* Prevent unused argument(s) compilation warning */
402 /* NOTE : This function Should not be modified, when the callback is needed,
403 the HAL_I2S_MspInit could be implemented in the user file
408 * @brief I2S MSP DeInit
409 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
410 * the configuration information for I2S module
413 __weak
void HAL_I2S_MspDeInit(I2S_HandleTypeDef
*hi2s
)
415 /* Prevent unused argument(s) compilation warning */
417 /* NOTE : This function Should not be modified, when the callback is needed,
418 the HAL_I2S_MspDeInit could be implemented in the user file
425 /** @defgroup I2S_Exported_Functions_Group2 IO operation functions
426 * @brief Data transfers functions
429 ===============================================================================
430 ##### IO operation functions #####
431 ===============================================================================
433 This subsection provides a set of functions allowing to manage the I2S data
436 (#) There are two modes of transfer:
437 (++) Blocking mode : The communication is performed in the polling mode.
438 The status of all data processing is returned by the same function
439 after finishing transfer.
440 (++) No-Blocking mode : The communication is performed using Interrupts
441 or DMA. These functions return the status of the transfer startup.
442 The end of the data processing will be indicated through the
443 dedicated I2S IRQ when using Interrupt mode or the DMA IRQ when
446 (#) Blocking mode functions are :
447 (++) HAL_I2S_Transmit()
448 (++) HAL_I2S_Receive()
450 (#) No-Blocking mode functions with Interrupt are :
451 (++) HAL_I2S_Transmit_IT()
452 (++) HAL_I2S_Receive_IT()
454 (#) No-Blocking mode functions with DMA are :
455 (++) HAL_I2S_Transmit_DMA()
456 (++) HAL_I2S_Receive_DMA()
458 (#) A set of Transfer Complete Callbacks are provided in non Blocking mode:
459 (++) HAL_I2S_TxCpltCallback()
460 (++) HAL_I2S_RxCpltCallback()
461 (++) HAL_I2S_ErrorCallback()
468 * @brief Transmit an amount of data in blocking mode
469 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
470 * the configuration information for I2S module
471 * @param pData: a 16-bit pointer to data buffer.
472 * @param Size: number of data sample to be sent:
473 * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S
474 * configuration phase, the Size parameter means the number of 16-bit data length
475 * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected
476 * the Size parameter means the number of 16-bit data length.
477 * @param Timeout: Timeout duration
478 * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization
479 * between Master and Slave(example: audio streaming).
482 HAL_StatusTypeDef
HAL_I2S_Transmit(I2S_HandleTypeDef
*hi2s
, uint16_t *pData
, uint16_t Size
, uint32_t Timeout
)
486 if((pData
== NULL
) || (Size
== 0U))
491 if(hi2s
->State
== HAL_I2S_STATE_READY
)
493 tmp1
= hi2s
->Instance
->I2SCFGR
& (SPI_I2SCFGR_DATLEN
| SPI_I2SCFGR_CHLEN
);
495 if((tmp1
== I2S_DATAFORMAT_24B
) || (tmp1
== I2S_DATAFORMAT_32B
))
497 hi2s
->TxXferSize
= (Size
<< 1U);
498 hi2s
->TxXferCount
= (Size
<< 1U);
502 hi2s
->TxXferSize
= Size
;
503 hi2s
->TxXferCount
= Size
;
509 hi2s
->ErrorCode
= HAL_I2S_ERROR_NONE
;
510 hi2s
->State
= HAL_I2S_STATE_BUSY_TX
;
512 /* Check if the I2S is already enabled */
513 if((hi2s
->Instance
->I2SCFGR
&SPI_I2SCFGR_I2SE
) != SPI_I2SCFGR_I2SE
)
515 /* Enable I2S peripheral */
516 __HAL_I2S_ENABLE(hi2s
);
519 while(hi2s
->TxXferCount
> 0U)
521 hi2s
->Instance
->DR
= (*pData
++);
524 /* Wait until TXE flag is set */
525 if (I2S_WaitFlagStateUntilTimeout(hi2s
, I2S_FLAG_TXE
, SET
, Timeout
) != HAL_OK
)
527 /* Set the error code and execute error callback*/
528 SET_BIT(hi2s
->ErrorCode
, HAL_I2S_ERROR_TIMEOUT
);
529 HAL_I2S_ErrorCallback(hi2s
);
533 /* Check if an underrun occurs */
534 if(__HAL_I2S_GET_FLAG(hi2s
, I2S_FLAG_UDR
) == SET
)
536 /* Clear underrun flag */
537 __HAL_I2S_CLEAR_UDRFLAG(hi2s
);
538 /* Set the I2S State ready */
539 hi2s
->State
= HAL_I2S_STATE_READY
;
541 /* Process Unlocked */
544 /* Set the error code and execute error callback*/
545 SET_BIT(hi2s
->ErrorCode
, HAL_I2S_ERROR_UDR
);
546 HAL_I2S_ErrorCallback(hi2s
);
551 hi2s
->State
= HAL_I2S_STATE_READY
;
553 /* Process Unlocked */
565 * @brief Receive an amount of data in blocking mode
566 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
567 * the configuration information for I2S module
568 * @param pData: a 16-bit pointer to data buffer
569 * @param Size: number of data sample to be sent:
570 * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S
571 * configuration phase, the Size parameter means the number of 16-bit data length
572 * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected
573 * the Size parameter means the number of 16-bit data length.
574 * @param Timeout: Timeout duration
575 * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization
576 * between Master and Slave(example: audio streaming)
577 * @note In I2S Master Receiver mode, just after enabling the peripheral the clock will be generate
578 * in continuous way and as the I2S is not disabled at the end of the I2S transaction
581 HAL_StatusTypeDef
HAL_I2S_Receive(I2S_HandleTypeDef
*hi2s
, uint16_t *pData
, uint16_t Size
, uint32_t Timeout
)
585 if((pData
== NULL
) || (Size
== 0U))
590 if(hi2s
->State
== HAL_I2S_STATE_READY
)
592 tmp1
= hi2s
->Instance
->I2SCFGR
& (SPI_I2SCFGR_DATLEN
| SPI_I2SCFGR_CHLEN
);
593 if((tmp1
== I2S_DATAFORMAT_24B
) || (tmp1
== I2S_DATAFORMAT_32B
))
595 hi2s
->RxXferSize
= (Size
<< 1U);
596 hi2s
->RxXferCount
= (Size
<< 1U);
600 hi2s
->RxXferSize
= Size
;
601 hi2s
->RxXferCount
= Size
;
606 hi2s
->ErrorCode
= HAL_I2S_ERROR_NONE
;
607 hi2s
->State
= HAL_I2S_STATE_BUSY_RX
;
609 /* Check if the I2S is already enabled */
610 if((hi2s
->Instance
->I2SCFGR
& SPI_I2SCFGR_I2SE
) != SPI_I2SCFGR_I2SE
)
612 /* Enable I2S peripheral */
613 __HAL_I2S_ENABLE(hi2s
);
616 /* Check if Master Receiver mode is selected */
617 if((hi2s
->Instance
->I2SCFGR
& SPI_I2SCFGR_I2SCFG
) == I2S_MODE_MASTER_RX
)
619 /* Clear the Overrun Flag by a read operation on the SPI_DR register followed by a read
620 access to the SPI_SR register. */
621 __HAL_I2S_CLEAR_OVRFLAG(hi2s
);
625 while(hi2s
->RxXferCount
> 0U)
627 /* Wait until RXNE flag is set */
628 if (I2S_WaitFlagStateUntilTimeout(hi2s
, I2S_FLAG_RXNE
, SET
, Timeout
) != HAL_OK
)
630 /* Set the error code and execute error callback*/
631 SET_BIT(hi2s
->ErrorCode
,HAL_I2S_ERROR_TIMEOUT
);
632 HAL_I2S_ErrorCallback(hi2s
);
636 /* Check if an overrun occurs */
637 if(__HAL_I2S_GET_FLAG(hi2s
, I2S_FLAG_OVR
) == SET
)
639 /* Clear overrun flag */
640 __HAL_I2S_CLEAR_OVRFLAG(hi2s
);
642 /* Set the I2S State ready */
643 hi2s
->State
= HAL_I2S_STATE_READY
;
645 /* Process Unlocked */
648 /* Set the error code and execute error callback*/
649 SET_BIT(hi2s
->ErrorCode
, HAL_I2S_ERROR_OVR
);
650 HAL_I2S_ErrorCallback(hi2s
);
655 (*pData
++) = hi2s
->Instance
->DR
;
659 hi2s
->State
= HAL_I2S_STATE_READY
;
661 /* Process Unlocked */
673 * @brief Transmit an amount of data in non-blocking mode with Interrupt
674 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
675 * the configuration information for I2S module
676 * @param pData: a 16-bit pointer to data buffer.
677 * @param Size: number of data sample to be sent:
678 * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S
679 * configuration phase, the Size parameter means the number of 16-bit data length
680 * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected
681 * the Size parameter means the number of 16-bit data length.
682 * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization
683 * between Master and Slave(example: audio streaming).
686 HAL_StatusTypeDef
HAL_I2S_Transmit_IT(I2S_HandleTypeDef
*hi2s
, uint16_t *pData
, uint16_t Size
)
690 if(hi2s
->State
== HAL_I2S_STATE_READY
)
692 if((pData
== NULL
) || (Size
== 0U))
697 hi2s
->pTxBuffPtr
= pData
;
698 tmp1
= hi2s
->Instance
->I2SCFGR
& (SPI_I2SCFGR_DATLEN
| SPI_I2SCFGR_CHLEN
);
699 if((tmp1
== I2S_DATAFORMAT_24B
) || (tmp1
== I2S_DATAFORMAT_32B
))
701 hi2s
->TxXferSize
= (Size
<< 1U);
702 hi2s
->TxXferCount
= (Size
<< 1U);
706 hi2s
->TxXferSize
= Size
;
707 hi2s
->TxXferCount
= Size
;
713 hi2s
->State
= HAL_I2S_STATE_BUSY_TX
;
714 hi2s
->ErrorCode
= HAL_I2S_ERROR_NONE
;
716 /* Enable TXE and ERR interrupt */
717 __HAL_I2S_ENABLE_IT(hi2s
, (I2S_IT_TXE
| I2S_IT_ERR
));
719 /* Check if the I2S is already enabled */
720 if((hi2s
->Instance
->I2SCFGR
&SPI_I2SCFGR_I2SE
) != SPI_I2SCFGR_I2SE
)
722 /* Enable I2S peripheral */
723 __HAL_I2S_ENABLE(hi2s
);
726 /* Process Unlocked */
738 * @brief Receive an amount of data in non-blocking mode with Interrupt
739 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
740 * the configuration information for I2S module
741 * @param pData: a 16-bit pointer to the Receive data buffer.
742 * @param Size: number of data sample to be sent:
743 * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S
744 * configuration phase, the Size parameter means the number of 16-bit data length
745 * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected
746 * the Size parameter means the number of 16-bit data length.
747 * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization
748 * between Master and Slave(example: audio streaming).
749 * @note It is recommended to use DMA for the I2S receiver to avoid de-synchronisation
750 * between Master and Slave otherwise the I2S interrupt should be optimized.
753 HAL_StatusTypeDef
HAL_I2S_Receive_IT(I2S_HandleTypeDef
*hi2s
, uint16_t *pData
, uint16_t Size
)
757 if(hi2s
->State
== HAL_I2S_STATE_READY
)
759 if((pData
== NULL
) || (Size
== 0U))
764 hi2s
->pRxBuffPtr
= pData
;
765 tmp1
= hi2s
->Instance
->I2SCFGR
& (SPI_I2SCFGR_DATLEN
| SPI_I2SCFGR_CHLEN
);
766 if((tmp1
== I2S_DATAFORMAT_24B
) || (tmp1
== I2S_DATAFORMAT_32B
))
768 hi2s
->RxXferSize
= (Size
<< 1U);
769 hi2s
->RxXferCount
= (Size
<< 1U);
773 hi2s
->RxXferSize
= Size
;
774 hi2s
->RxXferCount
= Size
;
779 hi2s
->State
= HAL_I2S_STATE_BUSY_RX
;
780 hi2s
->ErrorCode
= HAL_I2S_ERROR_NONE
;
782 /* Enable TXE and ERR interrupt */
783 __HAL_I2S_ENABLE_IT(hi2s
, (I2S_IT_RXNE
| I2S_IT_ERR
));
785 /* Check if the I2S is already enabled */
786 if((hi2s
->Instance
->I2SCFGR
&SPI_I2SCFGR_I2SE
) != SPI_I2SCFGR_I2SE
)
788 /* Enable I2S peripheral */
789 __HAL_I2S_ENABLE(hi2s
);
792 /* Process Unlocked */
805 * @brief Transmit an amount of data in non-blocking mode with DMA
806 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
807 * the configuration information for I2S module
808 * @param pData: a 16-bit pointer to the Transmit data buffer.
809 * @param Size: number of data sample to be sent:
810 * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S
811 * configuration phase, the Size parameter means the number of 16-bit data length
812 * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected
813 * the Size parameter means the number of 16-bit data length.
814 * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization
815 * between Master and Slave(example: audio streaming).
818 HAL_StatusTypeDef
HAL_I2S_Transmit_DMA(I2S_HandleTypeDef
*hi2s
, uint16_t *pData
, uint16_t Size
)
820 uint32_t *tmp
= NULL
;
823 if((pData
== NULL
) || (Size
== 0U))
828 if(hi2s
->State
== HAL_I2S_STATE_READY
)
830 hi2s
->pTxBuffPtr
= pData
;
831 tmp1
= hi2s
->Instance
->I2SCFGR
& (SPI_I2SCFGR_DATLEN
| SPI_I2SCFGR_CHLEN
);
832 if((tmp1
== I2S_DATAFORMAT_24B
) || (tmp1
== I2S_DATAFORMAT_32B
))
834 hi2s
->TxXferSize
= (Size
<< 1U);
835 hi2s
->TxXferCount
= (Size
<< 1U);
839 hi2s
->TxXferSize
= Size
;
840 hi2s
->TxXferCount
= Size
;
846 hi2s
->ErrorCode
= HAL_I2S_ERROR_NONE
;
847 hi2s
->State
= HAL_I2S_STATE_BUSY_TX
;
849 /* Set the I2S Tx DMA Half transfer complete callback */
850 hi2s
->hdmatx
->XferHalfCpltCallback
= I2S_DMATxHalfCplt
;
852 /* Set the I2S Tx DMA transfer complete callback */
853 hi2s
->hdmatx
->XferCpltCallback
= I2S_DMATxCplt
;
855 /* Set the DMA error callback */
856 hi2s
->hdmatx
->XferErrorCallback
= I2S_DMAError
;
858 /* Enable the Tx DMA Stream */
859 tmp
= (uint32_t*)&pData
;
860 HAL_DMA_Start_IT(hi2s
->hdmatx
, *(uint32_t*)tmp
, (uint32_t)&hi2s
->Instance
->DR
, hi2s
->TxXferSize
);
862 /* Check if the I2S is already enabled */
863 if((hi2s
->Instance
->I2SCFGR
&SPI_I2SCFGR_I2SE
) != SPI_I2SCFGR_I2SE
)
865 /* Enable I2S peripheral */
866 __HAL_I2S_ENABLE(hi2s
);
869 /* Check if the I2S Tx request is already enabled */
870 if((hi2s
->Instance
->CR2
& SPI_CR2_TXDMAEN
) != SPI_CR2_TXDMAEN
)
872 /* Enable Tx DMA Request */
873 SET_BIT(hi2s
->Instance
->CR2
, SPI_CR2_TXDMAEN
);
876 /* Process Unlocked */
888 * @brief Receive an amount of data in non-blocking mode with DMA
889 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
890 * the configuration information for I2S module
891 * @param pData: a 16-bit pointer to the Receive data buffer.
892 * @param Size: number of data sample to be sent:
893 * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S
894 * configuration phase, the Size parameter means the number of 16-bit data length
895 * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected
896 * the Size parameter means the number of 16-bit data length.
897 * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization
898 * between Master and Slave(example: audio streaming).
901 HAL_StatusTypeDef
HAL_I2S_Receive_DMA(I2S_HandleTypeDef
*hi2s
, uint16_t *pData
, uint16_t Size
)
903 uint32_t *tmp
= NULL
;
906 if((pData
== NULL
) || (Size
== 0U))
911 if(hi2s
->State
== HAL_I2S_STATE_READY
)
913 hi2s
->pRxBuffPtr
= pData
;
914 tmp1
= hi2s
->Instance
->I2SCFGR
& (SPI_I2SCFGR_DATLEN
| SPI_I2SCFGR_CHLEN
);
915 if((tmp1
== I2S_DATAFORMAT_24B
) || (tmp1
== I2S_DATAFORMAT_32B
))
917 hi2s
->RxXferSize
= (Size
<< 1U);
918 hi2s
->RxXferCount
= (Size
<< 1U);
922 hi2s
->RxXferSize
= Size
;
923 hi2s
->RxXferCount
= Size
;
928 hi2s
->State
= HAL_I2S_STATE_BUSY_RX
;
929 hi2s
->ErrorCode
= HAL_I2S_ERROR_NONE
;
931 /* Set the I2S Rx DMA Half transfer complete callback */
932 hi2s
->hdmarx
->XferHalfCpltCallback
= I2S_DMARxHalfCplt
;
934 /* Set the I2S Rx DMA transfer complete callback */
935 hi2s
->hdmarx
->XferCpltCallback
= I2S_DMARxCplt
;
937 /* Set the DMA error callback */
938 hi2s
->hdmarx
->XferErrorCallback
= I2S_DMAError
;
940 /* Check if Master Receiver mode is selected */
941 if((hi2s
->Instance
->I2SCFGR
& SPI_I2SCFGR_I2SCFG
) == I2S_MODE_MASTER_RX
)
943 /* Clear the Overrun Flag by a read operation to the SPI_DR register followed by a read
944 access to the SPI_SR register. */
945 __HAL_I2S_CLEAR_OVRFLAG(hi2s
);
948 /* Enable the Rx DMA Stream */
949 tmp
= (uint32_t*)&pData
;
950 HAL_DMA_Start_IT(hi2s
->hdmarx
, (uint32_t)&hi2s
->Instance
->DR
, *(uint32_t*)tmp
, hi2s
->RxXferSize
);
952 /* Check if the I2S is already enabled */
953 if((hi2s
->Instance
->I2SCFGR
&SPI_I2SCFGR_I2SE
) != SPI_I2SCFGR_I2SE
)
955 /* Enable I2S peripheral */
956 __HAL_I2S_ENABLE(hi2s
);
959 /* Check if the I2S Rx request is already enabled */
960 if((hi2s
->Instance
->CR2
&SPI_CR2_RXDMAEN
) != SPI_CR2_RXDMAEN
)
962 /* Enable Rx DMA Request */
963 SET_BIT(hi2s
->Instance
->CR2
,SPI_CR2_RXDMAEN
);
966 /* Process Unlocked */
978 * @brief Pauses the audio channel playing from the Media.
979 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
980 * the configuration information for I2S module
983 HAL_StatusTypeDef
HAL_I2S_DMAPause(I2S_HandleTypeDef
*hi2s
)
988 if(hi2s
->State
== HAL_I2S_STATE_BUSY_TX
)
990 /* Disable the I2S DMA Tx request */
991 CLEAR_BIT(hi2s
->Instance
->CR2
,SPI_CR2_TXDMAEN
);
993 else if(hi2s
->State
== HAL_I2S_STATE_BUSY_RX
)
995 /* Disable the I2S DMA Rx request */
996 CLEAR_BIT(hi2s
->Instance
->CR2
,SPI_CR2_RXDMAEN
);
999 /* Process Unlocked */
1006 * @brief Resumes the audio channel playing from the Media.
1007 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1008 * the configuration information for I2S module
1009 * @retval HAL status
1011 HAL_StatusTypeDef
HAL_I2S_DMAResume(I2S_HandleTypeDef
*hi2s
)
1013 /* Process Locked */
1016 if(hi2s
->State
== HAL_I2S_STATE_BUSY_TX
)
1018 /* Enable the I2S DMA Tx request */
1019 SET_BIT(hi2s
->Instance
->CR2
,SPI_CR2_TXDMAEN
);
1021 else if(hi2s
->State
== HAL_I2S_STATE_BUSY_RX
)
1023 /* Enable the I2S DMA Rx request */
1024 SET_BIT(hi2s
->Instance
->CR2
,SPI_CR2_RXDMAEN
);
1027 /* If the I2S peripheral is still not enabled, enable it */
1028 if ((hi2s
->Instance
->I2SCFGR
& SPI_I2SCFGR_I2SE
) == 0U)
1030 /* Enable I2S peripheral */
1031 __HAL_I2S_ENABLE(hi2s
);
1034 /* Process Unlocked */
1041 * @brief Resumes the audio channel playing from the Media.
1042 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1043 * the configuration information for I2S module
1044 * @retval HAL status
1046 HAL_StatusTypeDef
HAL_I2S_DMAStop(I2S_HandleTypeDef
*hi2s
)
1048 /* Process Locked */
1051 if(hi2s
->State
== HAL_I2S_STATE_BUSY_TX
)
1053 /* Disable the I2S DMA requests */
1054 CLEAR_BIT(hi2s
->Instance
->CR2
,SPI_CR2_TXDMAEN
);
1056 /* Disable the I2S DMA Channel */
1057 HAL_DMA_Abort(hi2s
->hdmatx
);
1059 else if(hi2s
->State
== HAL_I2S_STATE_BUSY_RX
)
1061 /* Disable the I2S DMA requests */
1062 CLEAR_BIT(hi2s
->Instance
->CR2
,SPI_CR2_RXDMAEN
);
1064 /* Disable the I2S DMA Channel */
1065 HAL_DMA_Abort(hi2s
->hdmarx
);
1067 /* Disable I2S peripheral */
1068 __HAL_I2S_DISABLE(hi2s
);
1070 hi2s
->State
= HAL_I2S_STATE_READY
;
1072 /* Process Unlocked */
1079 * @brief This function handles I2S interrupt request.
1080 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1081 * the configuration information for I2S module
1084 void HAL_I2S_IRQHandler(I2S_HandleTypeDef
*hi2s
)
1086 /* Call the IrqHandler ISR set during HAL_I2S_INIT */
1087 hi2s
->IrqHandlerISR(hi2s
);
1091 * @brief Tx Transfer Half completed callbacks
1092 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1093 * the configuration information for I2S module
1096 __weak
void HAL_I2S_TxHalfCpltCallback(I2S_HandleTypeDef
*hi2s
)
1098 /* Prevent unused argument(s) compilation warning */
1100 /* NOTE : This function Should not be modified, when the callback is needed,
1101 the HAL_I2S_TxHalfCpltCallback could be implemented in the user file
1106 * @brief Tx Transfer completed callbacks
1107 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1108 * the configuration information for I2S module
1111 __weak
void HAL_I2S_TxCpltCallback(I2S_HandleTypeDef
*hi2s
)
1113 /* Prevent unused argument(s) compilation warning */
1115 /* NOTE : This function Should not be modified, when the callback is needed,
1116 the HAL_I2S_TxCpltCallback could be implemented in the user file
1121 * @brief Rx Transfer half completed callbacks
1122 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1123 * the configuration information for I2S module
1126 __weak
void HAL_I2S_RxHalfCpltCallback(I2S_HandleTypeDef
*hi2s
)
1128 /* Prevent unused argument(s) compilation warning */
1130 /* NOTE : This function Should not be modified, when the callback is needed,
1131 the HAL_I2S_RxHalfCpltCallback could be implemented in the user file
1136 * @brief Rx Transfer completed callbacks
1137 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1138 * the configuration information for I2S module
1141 __weak
void HAL_I2S_RxCpltCallback(I2S_HandleTypeDef
*hi2s
)
1143 /* Prevent unused argument(s) compilation warning */
1145 /* NOTE : This function Should not be modified, when the callback is needed,
1146 the HAL_I2S_RxCpltCallback could be implemented in the user file
1151 * @brief I2S error callbacks
1152 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1153 * the configuration information for I2S module
1156 __weak
void HAL_I2S_ErrorCallback(I2S_HandleTypeDef
*hi2s
)
1158 /* Prevent unused argument(s) compilation warning */
1160 /* NOTE : This function Should not be modified, when the callback is needed,
1161 the HAL_I2S_ErrorCallback could be implemented in the user file
1169 /** @defgroup I2S_Exported_Functions_Group3 Peripheral State and Errors functions
1170 * @brief Peripheral State functions
1173 ===============================================================================
1174 ##### Peripheral State and Errors functions #####
1175 ===============================================================================
1177 This subsection permits to get in run-time the status of the peripheral
1185 * @brief Return the I2S state
1186 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1187 * the configuration information for I2S module
1190 HAL_I2S_StateTypeDef
HAL_I2S_GetState(I2S_HandleTypeDef
*hi2s
)
1196 * @brief Return the I2S error code
1197 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1198 * the configuration information for I2S module
1199 * @retval I2S Error Code
1201 uint32_t HAL_I2S_GetError(I2S_HandleTypeDef
*hi2s
)
1203 return hi2s
->ErrorCode
;
1213 /* Private functions ---------------------------------------------------------*/
1214 /** @addtogroup I2S_Private_Functions I2S Private Functions
1218 * @brief DMA I2S transmit process complete callback
1219 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1220 * the configuration information for the specified DMA module.
1223 static void I2S_DMATxCplt(DMA_HandleTypeDef
*hdma
)
1225 I2S_HandleTypeDef
* hi2s
= ( I2S_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
1227 if(HAL_IS_BIT_CLR(hdma
->Instance
->CCR
, DMA_CCR_CIRC
))
1229 /* Disable Tx DMA Request */
1230 CLEAR_BIT(hi2s
->Instance
->CR2
,SPI_CR2_TXDMAEN
);
1232 hi2s
->TxXferCount
= 0U;
1233 hi2s
->State
= HAL_I2S_STATE_READY
;
1235 HAL_I2S_TxCpltCallback(hi2s
);
1238 * @brief DMA I2S transmit process half complete callback
1239 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1240 * the configuration information for the specified DMA module.
1243 static void I2S_DMATxHalfCplt(DMA_HandleTypeDef
*hdma
)
1245 I2S_HandleTypeDef
* hi2s
= (I2S_HandleTypeDef
*)((DMA_HandleTypeDef
*)hdma
)->Parent
;
1247 HAL_I2S_TxHalfCpltCallback(hi2s
);
1251 * @brief DMA I2S receive process complete callback
1252 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1253 * the configuration information for the specified DMA module.
1256 static void I2S_DMARxCplt(DMA_HandleTypeDef
*hdma
)
1258 I2S_HandleTypeDef
* hi2s
= ( I2S_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
1260 if(HAL_IS_BIT_CLR(hdma
->Instance
->CCR
, DMA_CCR_CIRC
))
1262 /* Disable Rx DMA Request */
1263 CLEAR_BIT(hi2s
->Instance
->CR2
,SPI_CR2_RXDMAEN
);
1264 hi2s
->RxXferCount
= 0U;
1265 hi2s
->State
= HAL_I2S_STATE_READY
;
1267 HAL_I2S_RxCpltCallback(hi2s
);
1271 * @brief DMA I2S receive process half complete callback
1272 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1273 * the configuration information for the specified DMA module.
1276 static void I2S_DMARxHalfCplt(DMA_HandleTypeDef
*hdma
)
1278 I2S_HandleTypeDef
* hi2s
= (I2S_HandleTypeDef
*)((DMA_HandleTypeDef
*)hdma
)->Parent
;
1280 HAL_I2S_RxHalfCpltCallback(hi2s
);
1284 * @brief DMA I2S communication error callback
1285 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1286 * the configuration information for the specified DMA module.
1289 static void I2S_DMAError(DMA_HandleTypeDef
*hdma
)
1291 I2S_HandleTypeDef
* hi2s
= (I2S_HandleTypeDef
*)((DMA_HandleTypeDef
*)hdma
)->Parent
;
1293 /* Disable Rx and Tx DMA Request */
1294 CLEAR_BIT(hi2s
->Instance
->CR2
,(SPI_CR2_RXDMAEN
| SPI_CR2_TXDMAEN
));
1295 hi2s
->TxXferCount
= 0U;
1296 hi2s
->RxXferCount
= 0U;
1298 hi2s
->State
= HAL_I2S_STATE_READY
;
1300 SET_BIT(hi2s
->ErrorCode
,HAL_I2S_ERROR_DMA
);
1301 HAL_I2S_ErrorCallback(hi2s
);
1305 * @brief Transmit an amount of data in non-blocking mode with Interrupt
1306 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1307 * the configuration information for I2S module
1308 * @retval HAL status
1310 static void I2S_Transmit_IT(I2S_HandleTypeDef
*hi2s
)
1313 hi2s
->Instance
->DR
= (*hi2s
->pTxBuffPtr
++);
1314 hi2s
->TxXferCount
--;
1316 if(hi2s
->TxXferCount
== 0U)
1318 /* Disable TXE and ERR interrupt */
1319 __HAL_I2S_DISABLE_IT(hi2s
, (I2S_IT_TXE
| I2S_IT_ERR
));
1321 hi2s
->State
= HAL_I2S_STATE_READY
;
1322 HAL_I2S_TxCpltCallback(hi2s
);
1327 * @brief Receive an amount of data in non-blocking mode with Interrupt
1328 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1329 * the configuration information for I2S module
1330 * @retval HAL status
1332 static void I2S_Receive_IT(I2S_HandleTypeDef
*hi2s
)
1335 (*hi2s
->pRxBuffPtr
++) = hi2s
->Instance
->DR
;
1336 hi2s
->RxXferCount
--;
1338 if(hi2s
->RxXferCount
== 0U)
1340 /* Disable RXNE and ERR interrupt */
1341 __HAL_I2S_DISABLE_IT(hi2s
, (I2S_IT_RXNE
| I2S_IT_ERR
));
1343 hi2s
->State
= HAL_I2S_STATE_READY
;
1344 HAL_I2S_RxCpltCallback(hi2s
);
1349 * @brief This function handles I2S interrupt request.
1350 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1351 * the configuration information for I2S module
1354 static void I2S_IRQHandler(I2S_HandleTypeDef
*hi2s
)
1356 __IO
uint32_t i2ssr
= hi2s
->Instance
->SR
;
1358 if(hi2s
->State
== HAL_I2S_STATE_BUSY_RX
)
1360 /* I2S in mode Receiver ------------------------------------------------*/
1361 if(((i2ssr
& I2S_FLAG_RXNE
) == I2S_FLAG_RXNE
) && (__HAL_I2S_GET_IT_SOURCE(hi2s
, I2S_IT_RXNE
) != RESET
))
1363 I2S_Receive_IT(hi2s
);
1366 /* I2S Overrun error interrupt occured -------------------------------------*/
1367 if(((i2ssr
& I2S_FLAG_OVR
) == I2S_FLAG_OVR
) && (__HAL_I2S_GET_IT_SOURCE(hi2s
, I2S_IT_ERR
) != RESET
))
1369 /* Disable RXNE and ERR interrupt */
1370 __HAL_I2S_DISABLE_IT(hi2s
, (I2S_IT_RXNE
| I2S_IT_ERR
));
1372 /* Clear Overrun flag */
1373 __HAL_I2S_CLEAR_OVRFLAG(hi2s
);
1375 /* Set the I2S State ready */
1376 hi2s
->State
= HAL_I2S_STATE_READY
;
1379 /* Set the error code and execute error callback*/
1380 SET_BIT(hi2s
->ErrorCode
,HAL_I2S_ERROR_OVR
);
1381 HAL_I2S_ErrorCallback(hi2s
);
1385 if(hi2s
->State
== HAL_I2S_STATE_BUSY_TX
)
1387 /* I2S in mode Transmitter -----------------------------------------------*/
1388 if(((i2ssr
& I2S_FLAG_TXE
) == I2S_FLAG_TXE
) && (__HAL_I2S_GET_IT_SOURCE(hi2s
, I2S_IT_TXE
) != RESET
))
1390 I2S_Transmit_IT(hi2s
);
1393 /* I2S Underrun error interrupt occurred --------------------------------*/
1394 if(((i2ssr
& I2S_FLAG_UDR
) == I2S_FLAG_UDR
) && (__HAL_I2S_GET_IT_SOURCE(hi2s
, I2S_IT_ERR
) != RESET
))
1396 /* Disable TXE and ERR interrupt */
1397 __HAL_I2S_DISABLE_IT(hi2s
, (I2S_IT_TXE
| I2S_IT_ERR
));
1399 /* Clear Underrun flag */
1400 __HAL_I2S_CLEAR_UDRFLAG(hi2s
);
1402 /* Set the I2S State ready */
1403 hi2s
->State
= HAL_I2S_STATE_READY
;
1405 /* Set the error code and execute error callback*/
1406 SET_BIT(hi2s
->ErrorCode
, HAL_I2S_ERROR_UDR
);
1407 HAL_I2S_ErrorCallback(hi2s
);
1413 * @brief This function handles I2S Communication Timeout.
1414 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1415 * the configuration information for I2S module
1416 * @param Flag: Flag checked
1417 * @param State: Value of the flag expected
1418 * @param Timeout: Duration of the timeout
1419 * @retval HAL status
1421 static HAL_StatusTypeDef
I2S_WaitFlagStateUntilTimeout(I2S_HandleTypeDef
*hi2s
, uint32_t Flag
, uint32_t State
,
1424 uint32_t tickstart
= HAL_GetTick();
1426 /* Wait until flag is set to status*/
1427 while(((__HAL_I2S_GET_FLAG(hi2s
, Flag
)) ? SET
: RESET
) != State
)
1429 if(Timeout
!= HAL_MAX_DELAY
)
1431 if((Timeout
== 0U)||((HAL_GetTick() - tickstart
) > Timeout
))
1433 /* Set the I2S State ready */
1434 hi2s
->State
= HAL_I2S_STATE_READY
;
1436 /* Process Unlocked */
1454 #endif /* STM32F103xE || STM32F103xG || STM32F105xC || STM32F107xC */
1455 #endif /* HAL_I2S_MODULE_ENABLED */
1460 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/