before merging master
[inav.git] / lib / main / STM32F7 / Drivers / STM32F7xx_HAL_Driver / Src / stm32f7xx_hal_i2s.c
blob7cc338c187d26101c0e98fc29314a87398583747
1 /**
2 ******************************************************************************
3 * @file stm32f7xx_hal_i2s.c
4 * @author MCD Application Team
5 * @version V1.2.2
6 * @date 14-April-2017
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
13 @verbatim
14 ===============================================================================
15 ##### How to use this driver #####
16 ===============================================================================
17 [..]
18 The I2S HAL driver can be used as follows:
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 pull-up.
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
38 DMA Tx/Rx Channel.
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 -@- Make sure that either:
47 (+@) I2S clock is configured based on SYSCLK or
48 (+@) External clock source is configured after setting correctly
49 the define constant EXTERNAL_CLOCK_VALUE in the stm32f3xx_hal_conf.h file.
51 (#) Three mode of operations are available within this driver :
53 *** Polling mode IO operation ***
54 =================================
55 [..]
56 (+) Send an amount of data in blocking mode using HAL_I2S_Transmit()
57 (+) Receive an amount of data in blocking mode using HAL_I2S_Receive()
59 *** Interrupt mode IO operation ***
60 ===================================
61 [..]
62 (+) Send an amount of data in non blocking mode using HAL_I2S_Transmit_IT()
63 (+) At transmission end of half transfer HAL_I2S_TxHalfCpltCallback is executed and user can
64 add his own code by customization of function pointer HAL_I2S_TxHalfCpltCallback
65 (+) At transmission end of transfer HAL_I2S_TxCpltCallback is executed and user can
66 add his own code by customization of function pointer HAL_I2S_TxCpltCallback
67 (+) Receive an amount of data in non blocking mode using HAL_I2S_Receive_IT()
68 (+) At reception end of half transfer HAL_I2S_RxHalfCpltCallback is executed and user can
69 add his own code by customization of function pointer HAL_I2S_RxHalfCpltCallback
70 (+) At reception end of transfer HAL_I2S_RxCpltCallback is executed and user can
71 add his own code by customization of function pointer HAL_I2S_RxCpltCallback
72 (+) In case of transfer Error, HAL_I2S_ErrorCallback() function is executed and user can
73 add his own code by customization of function pointer HAL_I2S_ErrorCallback
75 *** DMA mode IO operation ***
76 ==============================
77 [..]
78 (+) Send an amount of data in non blocking mode (DMA) using HAL_I2S_Transmit_DMA()
79 (+) At transmission end of half transfer HAL_I2S_TxHalfCpltCallback is executed and user can
80 add his own code by customization of function pointer HAL_I2S_TxHalfCpltCallback
81 (+) At transmission end of transfer HAL_I2S_TxCpltCallback is executed and user can
82 add his own code by customization of function pointer HAL_I2S_TxCpltCallback
83 (+) Receive an amount of data in non blocking mode (DMA) using HAL_I2S_Receive_DMA()
84 (+) At reception end of half transfer HAL_I2S_RxHalfCpltCallback is executed and user can
85 add his own code by customization of function pointer HAL_I2S_RxHalfCpltCallback
86 (+) At reception end of transfer HAL_I2S_RxCpltCallback is executed and user can
87 add his own code by customization of function pointer HAL_I2S_RxCpltCallback
88 (+) In case of transfer Error, HAL_I2S_ErrorCallback() function is executed and user can
89 add his own code by customization of function pointer HAL_I2S_ErrorCallback
90 (+) Pause the DMA Transfer using HAL_I2S_DMAPause()
91 (+) Resume the DMA Transfer using HAL_I2S_DMAResume()
92 (+) Stop the DMA Transfer using HAL_I2S_DMAStop()
94 *** I2S HAL driver macros list ***
95 =============================================
96 [..]
97 Below the list of most used macros in I2S HAL driver.
99 (+) __HAL_I2S_ENABLE: Enable the specified SPI peripheral (in I2S mode)
100 (+) __HAL_I2S_DISABLE: Disable the specified SPI peripheral (in I2S mode)
101 (+) __HAL_I2S_ENABLE_IT : Enable the specified I2S interrupts
102 (+) __HAL_I2S_DISABLE_IT : Disable the specified I2S interrupts
103 (+) __HAL_I2S_GET_FLAG: Check whether the specified I2S flag is set or not
105 [..]
106 (@) You can refer to the I2S HAL driver header file for more useful macros
108 @endverbatim
109 ******************************************************************************
110 * @attention
112 * <h2><center>&copy; COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
114 * Redistribution and use in source and binary forms, with or without modification,
115 * are permitted provided that the following conditions are met:
116 * 1. Redistributions of source code must retain the above copyright notice,
117 * this list of conditions and the following disclaimer.
118 * 2. Redistributions in binary form must reproduce the above copyright notice,
119 * this list of conditions and the following disclaimer in the documentation
120 * and/or other materials provided with the distribution.
121 * 3. Neither the name of STMicroelectronics nor the names of its contributors
122 * may be used to endorse or promote products derived from this software
123 * without specific prior written permission.
125 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
126 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
127 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
128 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
129 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
130 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
131 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
132 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
133 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
134 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
136 ******************************************************************************
139 /* Includes ------------------------------------------------------------------*/
140 #include "stm32f7xx_hal.h"
142 /** @addtogroup STM32F7xx_HAL_Driver
143 * @{
146 /** @defgroup I2S I2S
147 * @brief I2S HAL module driver
148 * @{
151 #ifdef HAL_I2S_MODULE_ENABLED
153 /* Private typedef -----------------------------------------------------------*/
154 /* Private define ------------------------------------------------------------*/
155 /* Private macro -------------------------------------------------------------*/
156 /* Private variables ---------------------------------------------------------*/
157 /* Private function prototypes -----------------------------------------------*/
158 /** @defgroup I2S_Private_Functions I2S Private Functions
159 * @{
161 static void I2S_DMATxCplt(DMA_HandleTypeDef *hdma);
162 static void I2S_DMATxHalfCplt(DMA_HandleTypeDef *hdma);
163 static void I2S_DMARxCplt(DMA_HandleTypeDef *hdma);
164 static void I2S_DMARxHalfCplt(DMA_HandleTypeDef *hdma);
165 static void I2S_DMAError(DMA_HandleTypeDef *hdma);
166 static void I2S_Transmit_IT(I2S_HandleTypeDef *hi2s);
167 static void I2S_Receive_IT(I2S_HandleTypeDef *hi2s);
168 static uint32_t I2S_GetClockFreq(I2S_HandleTypeDef *hi2s);
169 static HAL_StatusTypeDef I2S_WaitFlagStateUntilTimeout(I2S_HandleTypeDef *hi2s, uint32_t Flag, uint32_t State, uint32_t Timeout);
171 * @}
174 /* Exported functions ---------------------------------------------------------*/
176 /** @defgroup I2S_Exported_Functions I2S Exported Functions
177 * @{
180 /** @defgroup I2S_Exported_Functions_Group1 Initialization and de-initialization functions
181 * @brief Initialization and Configuration functions
183 @verbatim
184 ===============================================================================
185 ##### Initialization and de-initialization functions #####
186 ===============================================================================
187 [..] This subsection provides a set of functions allowing to initialize and
188 de-initialize the I2Sx peripheral in simplex mode:
190 (+) User must Implement HAL_I2S_MspInit() function in which he configures
191 all related peripherals resources (CLOCK, GPIO, DMA, IT and NVIC ).
193 (+) Call the function HAL_I2S_Init() to configure the selected device with
194 the selected configuration:
195 (++) Mode
196 (++) Standard
197 (++) Data Format
198 (++) MCLK Output
199 (++) Audio frequency
200 (++) Polarity
201 (++) Full duplex mode
203 (+) Call the function HAL_I2S_DeInit() to restore the default configuration
204 of the selected I2Sx peripheral.
205 @endverbatim
206 * @{
210 * @brief Initializes the I2S according to the specified parameters
211 * in the I2S_InitTypeDef and create the associated handle.
212 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
213 * the configuration information for I2S module
214 * @retval HAL status
216 HAL_StatusTypeDef HAL_I2S_Init(I2S_HandleTypeDef *hi2s)
218 uint16_t tmpreg = 0, i2sdiv = 2, i2sodd = 0, packetlength = 1;
219 uint32_t tmp = 0, i2sclk = 0;
221 /* Check the I2S handle allocation */
222 if(hi2s == NULL)
224 return HAL_ERROR;
227 /* Check the parameters */
228 assert_param(IS_I2S_ALL_INSTANCE(hi2s->Instance));
229 assert_param(IS_I2S_MODE(hi2s->Init.Mode));
230 assert_param(IS_I2S_STANDARD(hi2s->Init.Standard));
231 assert_param(IS_I2S_DATA_FORMAT(hi2s->Init.DataFormat));
232 assert_param(IS_I2S_MCLK_OUTPUT(hi2s->Init.MCLKOutput));
233 assert_param(IS_I2S_AUDIO_FREQ(hi2s->Init.AudioFreq));
234 assert_param(IS_I2S_CPOL(hi2s->Init.CPOL));
235 assert_param(IS_I2S_CLOCKSOURCE(hi2s->Init.ClockSource));
237 if(hi2s->State == HAL_I2S_STATE_RESET)
239 /* Allocate lock resource and initialize it */
240 hi2s->Lock = HAL_UNLOCKED;
241 /* Init the low level hardware : GPIO, CLOCK, CORTEX...etc */
242 HAL_I2S_MspInit(hi2s);
245 hi2s->State = HAL_I2S_STATE_BUSY;
247 /*----------------------- SPIx I2SCFGR & I2SPR Configuration -----------------*/
248 /* Clear I2SMOD, I2SE, I2SCFG, PCMSYNC, I2SSTD, CKPOL, DATLEN and CHLEN bits */
249 hi2s->Instance->I2SCFGR &= ~(SPI_I2SCFGR_CHLEN | SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CKPOL | \
250 SPI_I2SCFGR_I2SSTD | SPI_I2SCFGR_PCMSYNC | SPI_I2SCFGR_I2SCFG | \
251 SPI_I2SCFGR_I2SE | SPI_I2SCFGR_I2SMOD);
252 hi2s->Instance->I2SPR = 0x0002;
254 /* Get the I2SCFGR register value */
255 tmpreg = hi2s->Instance->I2SCFGR;
257 /* If the default value has to be written, reinitialize i2sdiv and i2sodd*/
258 if(hi2s->Init.AudioFreq == I2S_AUDIOFREQ_DEFAULT)
260 i2sodd = (uint16_t)0;
261 i2sdiv = (uint16_t)2;
263 /* If the requested audio frequency is not the default, compute the prescaler */
264 else
266 /* Check the frame length (For the Prescaler computing) *******************/
267 if(hi2s->Init.DataFormat == I2S_DATAFORMAT_16B)
269 /* Packet length is 16 bits */
270 packetlength = 1;
272 else
274 /* Packet length is 32 bits */
275 packetlength = 2;
278 /* Get I2S source Clock frequency ****************************************/
280 /* If an external I2S clock has to be used, the specific define should be set
281 in the project configuration or in the stm32f3xx_conf.h file */
282 if(hi2s->Init.ClockSource == I2S_CLOCK_EXTERNAL)
284 /* Set the I2S clock to the external clock value */
285 i2sclk = EXTERNAL_CLOCK_VALUE;
287 else
289 /* Get the I2S source clock value */
290 i2sclk = I2S_GetClockFreq(hi2s);
293 /* Compute the Real divider depending on the MCLK output state, with a floating point */
294 if(hi2s->Init.MCLKOutput == I2S_MCLKOUTPUT_ENABLE)
296 /* MCLK output is enabled */
297 tmp = (uint16_t)(((((i2sclk / 256) * 10) / hi2s->Init.AudioFreq)) + 5);
299 else
301 /* MCLK output is disabled */
302 tmp = (uint16_t)(((((i2sclk / (32 * packetlength)) *10 ) / hi2s->Init.AudioFreq)) + 5);
305 /* Remove the flatting point */
306 tmp = tmp / 10;
308 /* Check the parity of the divider */
309 i2sodd = (uint16_t)(tmp & (uint16_t)0x0001);
311 /* Compute the i2sdiv prescaler */
312 i2sdiv = (uint16_t)((tmp - i2sodd) / 2);
314 /* Get the Mask for the Odd bit (SPI_I2SPR[8]) register */
315 i2sodd = (uint16_t) (i2sodd << 8);
318 /* Test if the divider is 1 or 0 or greater than 0xFF */
319 if((i2sdiv < 2) || (i2sdiv > 0xFF))
321 /* Set the default values */
322 i2sdiv = 2;
323 i2sodd = 0;
326 /* Write to SPIx I2SPR register the computed value */
327 hi2s->Instance->I2SPR = (uint16_t)((uint16_t)i2sdiv | (uint16_t)(i2sodd | (uint16_t)hi2s->Init.MCLKOutput));
329 /* Configure the I2S with the I2S_InitStruct values */
330 tmpreg |= (uint16_t)((uint16_t)SPI_I2SCFGR_I2SMOD | (uint16_t)(hi2s->Init.Mode | \
331 (uint16_t)(hi2s->Init.Standard | (uint16_t)(hi2s->Init.DataFormat | \
332 (uint16_t)hi2s->Init.CPOL))));
334 /* Write to SPIx I2SCFGR */
335 hi2s->Instance->I2SCFGR = tmpreg;
337 hi2s->ErrorCode = HAL_I2S_ERROR_NONE;
338 hi2s->State= HAL_I2S_STATE_READY;
340 return HAL_OK;
344 * @brief DeInitializes the I2S peripheral
345 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
346 * the configuration information for I2S module
347 * @retval HAL status
349 HAL_StatusTypeDef HAL_I2S_DeInit(I2S_HandleTypeDef *hi2s)
351 /* Check the I2S handle allocation */
352 if(hi2s == NULL)
354 return HAL_ERROR;
357 /* Check the parameters */
358 assert_param(IS_I2S_ALL_INSTANCE(hi2s->Instance));
360 hi2s->State = HAL_I2S_STATE_BUSY;
362 /* DeInit the low level hardware: GPIO, CLOCK, NVIC... */
363 HAL_I2S_MspDeInit(hi2s);
365 hi2s->ErrorCode = HAL_I2S_ERROR_NONE;
366 hi2s->State = HAL_I2S_STATE_RESET;
368 /* Release Lock */
369 __HAL_UNLOCK(hi2s);
371 return HAL_OK;
375 * @brief I2S MSP Init
376 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
377 * the configuration information for I2S module
378 * @retval None
380 __weak void HAL_I2S_MspInit(I2S_HandleTypeDef *hi2s)
382 /* Prevent unused argument(s) compilation warning */
383 UNUSED(hi2s);
385 /* NOTE : This function Should not be modified, when the callback is needed,
386 the HAL_I2S_MspInit could be implemented in the user file
391 * @brief I2S MSP DeInit
392 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
393 * the configuration information for I2S module
394 * @retval None
396 __weak void HAL_I2S_MspDeInit(I2S_HandleTypeDef *hi2s)
398 /* Prevent unused argument(s) compilation warning */
399 UNUSED(hi2s);
401 /* NOTE : This function Should not be modified, when the callback is needed,
402 the HAL_I2S_MspDeInit could be implemented in the user file
407 * @}
410 /** @defgroup I2S_Exported_Functions_Group2 Input and Output operation functions
411 * @brief Data transfers functions
413 @verbatim
414 ===============================================================================
415 ##### IO operation functions #####
416 ===============================================================================
417 [..]
418 This subsection provides a set of functions allowing to manage the I2S data
419 transfers.
421 (#) There are two modes of transfer:
422 (++) Blocking mode : The communication is performed in the polling mode.
423 The status of all data processing is returned by the same function
424 after finishing transfer.
425 (++) No-Blocking mode : The communication is performed using Interrupts
426 or DMA. These functions return the status of the transfer startup.
427 The end of the data processing will be indicated through the
428 dedicated I2S IRQ when using Interrupt mode or the DMA IRQ when
429 using DMA mode.
431 (#) Blocking mode functions are :
432 (++) HAL_I2S_Transmit()
433 (++) HAL_I2S_Receive()
435 (#) No-Blocking mode functions with Interrupt are :
436 (++) HAL_I2S_Transmit_IT()
437 (++) HAL_I2S_Receive_IT()
439 (#) No-Blocking mode functions with DMA are :
440 (++) HAL_I2S_Transmit_DMA()
441 (++) HAL_I2S_Receive_DMA()
443 (#) A set of Transfer Complete Callbacks are provided in non Blocking mode:
444 (++) HAL_I2S_TxCpltCallback()
445 (++) HAL_I2S_RxCpltCallback()
446 (++) HAL_I2S_ErrorCallback()
448 @endverbatim
449 * @{
453 * @brief Transmit an amount of data in blocking mode
454 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
455 * the configuration information for I2S module
456 * @param pData: a 16-bit pointer to data buffer.
457 * @param Size: number of data sample to be sent:
458 * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S
459 * configuration phase, the Size parameter means the number of 16-bit data length
460 * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected
461 * the Size parameter means the number of 16-bit data length.
462 * @param Timeout: Timeout duration
463 * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization
464 * between Master and Slave(example: audio streaming).
465 * @retval HAL status
467 HAL_StatusTypeDef HAL_I2S_Transmit(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size, uint32_t Timeout)
469 if((pData == NULL ) || (Size == 0))
471 return HAL_ERROR;
474 if(hi2s->State == HAL_I2S_STATE_READY)
476 if(((hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN)) == I2S_DATAFORMAT_24B)||\
477 ((hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN)) == I2S_DATAFORMAT_32B))
479 hi2s->TxXferSize = (Size << 1);
480 hi2s->TxXferCount = (Size << 1);
482 else
484 hi2s->TxXferSize = Size;
485 hi2s->TxXferCount = Size;
488 /* Process Locked */
489 __HAL_LOCK(hi2s);
491 hi2s->ErrorCode = HAL_I2S_ERROR_NONE;
492 hi2s->State = HAL_I2S_STATE_BUSY_TX;
494 /* Check if the I2S is already enabled */
495 if((hi2s->Instance->I2SCFGR &SPI_I2SCFGR_I2SE) != SPI_I2SCFGR_I2SE)
497 /* Enable I2S peripheral */
498 __HAL_I2S_ENABLE(hi2s);
501 while(hi2s->TxXferCount > 0)
503 hi2s->Instance->DR = (*pData++);
504 hi2s->TxXferCount--;
505 /* Wait until TXE flag is set */
506 if (I2S_WaitFlagStateUntilTimeout(hi2s, I2S_FLAG_TXE, SET, Timeout) != HAL_OK)
508 /* Set the error code and execute error callback*/
509 hi2s->ErrorCode |= HAL_I2S_ERROR_TIMEOUT;
510 HAL_I2S_ErrorCallback(hi2s);
511 return HAL_TIMEOUT;
514 /* Check if an underrun occurs */
515 if(__HAL_I2S_GET_FLAG(hi2s, I2S_FLAG_UDR) == SET)
517 /* Set the I2S State ready */
518 hi2s->State = HAL_I2S_STATE_READY;
520 /* Process Unlocked */
521 __HAL_UNLOCK(hi2s);
523 /* Set the error code and execute error callback*/
524 hi2s->ErrorCode |= HAL_I2S_ERROR_UDR;
525 HAL_I2S_ErrorCallback(hi2s);
527 return HAL_ERROR;
531 /* Check if Slave mode is selected */
532 if(((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SCFG) == I2S_MODE_SLAVE_TX) || ((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SCFG) == I2S_MODE_SLAVE_RX))
534 /* Wait until Busy flag is reset */
535 if (I2S_WaitFlagStateUntilTimeout(hi2s, I2S_FLAG_BSY, SET, Timeout) != HAL_OK)
537 /* Set the error code and execute error callback*/
538 hi2s->ErrorCode |= HAL_I2S_ERROR_TIMEOUT;
539 HAL_I2S_ErrorCallback(hi2s);
540 return HAL_TIMEOUT;
544 hi2s->State = HAL_I2S_STATE_READY;
546 /* Process Unlocked */
547 __HAL_UNLOCK(hi2s);
549 return HAL_OK;
551 else
553 return HAL_BUSY;
558 * @brief Receive an amount of data in blocking mode
559 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
560 * the configuration information for I2S module
561 * @param pData: a 16-bit pointer to data buffer.
562 * @param Size: number of data sample to be sent:
563 * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S
564 * configuration phase, the Size parameter means the number of 16-bit data length
565 * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected
566 * the Size parameter means the number of 16-bit data length.
567 * @param Timeout: Timeout duration
568 * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization
569 * between Master and Slave(example: audio streaming).
570 * @note In I2S Master Receiver mode, just after enabling the peripheral the clock will be generate
571 * in continuous way and as the I2S is not disabled at the end of the I2S transaction.
572 * @retval HAL status
574 HAL_StatusTypeDef HAL_I2S_Receive(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size, uint32_t Timeout)
576 if((pData == NULL ) || (Size == 0))
578 return HAL_ERROR;
581 if(hi2s->State == HAL_I2S_STATE_READY)
583 if(((hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN)) == I2S_DATAFORMAT_24B)||\
584 ((hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN)) == I2S_DATAFORMAT_32B))
586 hi2s->RxXferSize = (Size << 1);
587 hi2s->RxXferCount = (Size << 1);
589 else
591 hi2s->RxXferSize = Size;
592 hi2s->RxXferCount = Size;
594 /* Process Locked */
595 __HAL_LOCK(hi2s);
597 hi2s->ErrorCode = HAL_I2S_ERROR_NONE;
598 hi2s->State = HAL_I2S_STATE_BUSY_RX;
600 /* Check if the I2S is already enabled */
601 if((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SE) != SPI_I2SCFGR_I2SE)
603 /* Enable I2S peripheral */
604 __HAL_I2S_ENABLE(hi2s);
607 /* Check if Master Receiver mode is selected */
608 if((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SCFG) == I2S_MODE_MASTER_RX)
610 /* Clear the Overrun Flag by a read operation on the SPI_DR register followed by a read
611 access to the SPI_SR register. */
612 __HAL_I2S_CLEAR_OVRFLAG(hi2s);
615 /* Receive data */
616 while(hi2s->RxXferCount > 0)
618 /* Wait until RXNE flag is set */
619 if (I2S_WaitFlagStateUntilTimeout(hi2s, I2S_FLAG_RXNE, SET, Timeout) != HAL_OK)
621 /* Set the error code and execute error callback*/
622 hi2s->ErrorCode |= HAL_I2S_ERROR_TIMEOUT;
623 HAL_I2S_ErrorCallback(hi2s);
624 return HAL_TIMEOUT;
627 /* Check if an overrun occurs */
628 if(__HAL_I2S_GET_FLAG(hi2s, I2S_FLAG_OVR) == SET)
630 /* Set the I2S State ready */
631 hi2s->State = HAL_I2S_STATE_READY;
633 /* Process Unlocked */
634 __HAL_UNLOCK(hi2s);
636 /* Set the error code and execute error callback*/
637 hi2s->ErrorCode |= HAL_I2S_ERROR_OVR;
638 HAL_I2S_ErrorCallback(hi2s);
640 return HAL_ERROR;
643 (*pData++) = hi2s->Instance->DR;
644 hi2s->RxXferCount--;
647 hi2s->State = HAL_I2S_STATE_READY;
649 /* Process Unlocked */
650 __HAL_UNLOCK(hi2s);
652 return HAL_OK;
654 else
656 return HAL_BUSY;
661 * @brief Transmit an amount of data in non-blocking mode with Interrupt
662 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
663 * the configuration information for I2S module
664 * @param pData: a 16-bit pointer to data buffer.
665 * @param Size: number of data sample to be sent:
666 * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S
667 * configuration phase, the Size parameter means the number of 16-bit data length
668 * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected
669 * the Size parameter means the number of 16-bit data length.
670 * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization
671 * between Master and Slave(example: audio streaming).
672 * @retval HAL status
674 HAL_StatusTypeDef HAL_I2S_Transmit_IT(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size)
676 if(hi2s->State == HAL_I2S_STATE_READY)
678 if((pData == NULL) || (Size == 0))
680 return HAL_ERROR;
683 hi2s->pTxBuffPtr = pData;
684 if(((hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN)) == I2S_DATAFORMAT_24B)||\
685 ((hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN)) == I2S_DATAFORMAT_32B))
687 hi2s->TxXferSize = (Size << 1);
688 hi2s->TxXferCount = (Size << 1);
690 else
692 hi2s->TxXferSize = Size;
693 hi2s->TxXferCount = Size;
696 /* Process Locked */
697 __HAL_LOCK(hi2s);
699 hi2s->ErrorCode = HAL_I2S_ERROR_NONE;
700 hi2s->State = HAL_I2S_STATE_BUSY_TX;
702 /* Enable TXE and ERR interrupt */
703 __HAL_I2S_ENABLE_IT(hi2s, (I2S_IT_TXE | I2S_IT_ERR));
705 /* Check if the I2S is already enabled */
706 if((hi2s->Instance->I2SCFGR &SPI_I2SCFGR_I2SE) != SPI_I2SCFGR_I2SE)
708 /* Enable I2S peripheral */
709 __HAL_I2S_ENABLE(hi2s);
712 /* Process Unlocked */
713 __HAL_UNLOCK(hi2s);
715 return HAL_OK;
717 else
719 return HAL_BUSY;
724 * @brief Receive an amount of data in non-blocking mode with Interrupt
725 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
726 * the configuration information for I2S module
727 * @param pData: a 16-bit pointer to the Receive data buffer.
728 * @param Size: number of data sample to be sent:
729 * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S
730 * configuration phase, the Size parameter means the number of 16-bit data length
731 * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected
732 * the Size parameter means the number of 16-bit data length.
733 * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization
734 * between Master and Slave(example: audio streaming).
735 * @note It is recommended to use DMA for the I2S receiver to avoid de-synchronisation
736 * between Master and Slave otherwise the I2S interrupt should be optimized.
737 * @retval HAL status
739 HAL_StatusTypeDef HAL_I2S_Receive_IT(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size)
741 if(hi2s->State == HAL_I2S_STATE_READY)
743 if((pData == NULL) || (Size == 0))
745 return HAL_ERROR;
748 hi2s->pRxBuffPtr = pData;
749 if(((hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN)) == I2S_DATAFORMAT_24B)||\
750 ((hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN)) == I2S_DATAFORMAT_32B))
752 hi2s->RxXferSize = (Size << 1);
753 hi2s->RxXferCount = (Size << 1);
755 else
757 hi2s->RxXferSize = Size;
758 hi2s->RxXferCount = Size;
760 /* Process Locked */
761 __HAL_LOCK(hi2s);
763 hi2s->ErrorCode = HAL_I2S_ERROR_NONE;
764 hi2s->State = HAL_I2S_STATE_BUSY_RX;
766 /* Enable TXE and ERR interrupt */
767 __HAL_I2S_ENABLE_IT(hi2s, (I2S_IT_RXNE | I2S_IT_ERR));
769 /* Check if the I2S is already enabled */
770 if((hi2s->Instance->I2SCFGR &SPI_I2SCFGR_I2SE) != SPI_I2SCFGR_I2SE)
772 /* Enable I2S peripheral */
773 __HAL_I2S_ENABLE(hi2s);
776 /* Process Unlocked */
777 __HAL_UNLOCK(hi2s);
779 return HAL_OK;
781 else
783 return HAL_BUSY;
788 * @brief Transmit an amount of data in non-blocking mode with DMA
789 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
790 * the configuration information for I2S module
791 * @param pData: a 16-bit pointer to the Transmit data buffer.
792 * @param Size: number of data sample to be sent:
793 * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S
794 * configuration phase, the Size parameter means the number of 16-bit data length
795 * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected
796 * the Size parameter means the number of 16-bit data length.
797 * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization
798 * between Master and Slave(example: audio streaming).
799 * @retval HAL status
801 HAL_StatusTypeDef HAL_I2S_Transmit_DMA(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size)
803 uint32_t *tmp;
805 if((pData == NULL) || (Size == 0))
807 return HAL_ERROR;
810 if(hi2s->State == HAL_I2S_STATE_READY)
812 hi2s->pTxBuffPtr = pData;
813 if(((hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN)) == I2S_DATAFORMAT_24B)||\
814 ((hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN)) == I2S_DATAFORMAT_32B))
816 hi2s->TxXferSize = (Size << 1);
817 hi2s->TxXferCount = (Size << 1);
819 else
821 hi2s->TxXferSize = Size;
822 hi2s->TxXferCount = Size;
825 /* Process Locked */
826 __HAL_LOCK(hi2s);
828 hi2s->ErrorCode = HAL_I2S_ERROR_NONE;
829 hi2s->State = HAL_I2S_STATE_BUSY_TX;
831 /* Set the I2S Tx DMA Half transfer complete callback */
832 hi2s->hdmatx->XferHalfCpltCallback = I2S_DMATxHalfCplt;
834 /* Set the I2S TxDMA transfer complete callback */
835 hi2s->hdmatx->XferCpltCallback = I2S_DMATxCplt;
837 /* Set the DMA error callback */
838 hi2s->hdmatx->XferErrorCallback = I2S_DMAError;
840 /* Enable the Tx DMA Channel */
841 tmp = (uint32_t*)&pData;
842 HAL_DMA_Start_IT(hi2s->hdmatx, *(uint32_t*)tmp, (uint32_t)&hi2s->Instance->DR, hi2s->TxXferSize);
844 /* Check if the I2S is already enabled */
845 if((hi2s->Instance->I2SCFGR &SPI_I2SCFGR_I2SE) != SPI_I2SCFGR_I2SE)
847 /* Enable I2S peripheral */
848 __HAL_I2S_ENABLE(hi2s);
851 /* Enable Tx DMA Request */
852 hi2s->Instance->CR2 |= SPI_CR2_TXDMAEN;
854 /* Process Unlocked */
855 __HAL_UNLOCK(hi2s);
857 return HAL_OK;
859 else
861 return HAL_BUSY;
866 * @brief Receive an amount of data in non-blocking mode with DMA
867 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
868 * the configuration information for I2S module
869 * @param pData: a 16-bit pointer to the Receive data buffer.
870 * @param Size: number of data sample to be sent:
871 * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S
872 * configuration phase, the Size parameter means the number of 16-bit data length
873 * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected
874 * the Size parameter means the number of 16-bit data length.
875 * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization
876 * between Master and Slave(example: audio streaming).
877 * @retval HAL status
879 HAL_StatusTypeDef HAL_I2S_Receive_DMA(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size)
881 uint32_t *tmp;
883 if((pData == NULL) || (Size == 0))
885 return HAL_ERROR;
888 if(hi2s->State == HAL_I2S_STATE_READY)
890 hi2s->pRxBuffPtr = pData;
891 if(((hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN)) == I2S_DATAFORMAT_24B)||\
892 ((hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN)) == I2S_DATAFORMAT_32B))
894 hi2s->RxXferSize = (Size << 1);
895 hi2s->RxXferCount = (Size << 1);
897 else
899 hi2s->RxXferSize = Size;
900 hi2s->RxXferCount = Size;
902 /* Process Locked */
903 __HAL_LOCK(hi2s);
905 hi2s->ErrorCode = HAL_I2S_ERROR_NONE;
906 hi2s->State = HAL_I2S_STATE_BUSY_RX;
908 /* Set the I2S Rx DMA Half transfer complete callback */
909 hi2s->hdmarx->XferHalfCpltCallback = I2S_DMARxHalfCplt;
911 /* Set the I2S Rx DMA transfer complete callback */
912 hi2s->hdmarx->XferCpltCallback = I2S_DMARxCplt;
914 /* Set the DMA error callback */
915 hi2s->hdmarx->XferErrorCallback = I2S_DMAError;
917 /* Check if Master Receiver mode is selected */
918 if((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SCFG) == I2S_MODE_MASTER_RX)
920 /* Clear the Overrun Flag by a read operation to the SPI_DR register followed by a read
921 access to the SPI_SR register. */
922 __HAL_I2S_CLEAR_OVRFLAG(hi2s);
925 /* Enable the Rx DMA Channel */
926 tmp = (uint32_t*)&pData;
927 HAL_DMA_Start_IT(hi2s->hdmarx, (uint32_t)&hi2s->Instance->DR, *(uint32_t*)tmp, hi2s->RxXferSize);
929 /* Check if the I2S is already enabled */
930 if((hi2s->Instance->I2SCFGR &SPI_I2SCFGR_I2SE) != SPI_I2SCFGR_I2SE)
932 /* Enable I2S peripheral */
933 __HAL_I2S_ENABLE(hi2s);
936 /* Enable Rx DMA Request */
937 hi2s->Instance->CR2 |= SPI_CR2_RXDMAEN;
939 /* Process Unlocked */
940 __HAL_UNLOCK(hi2s);
942 return HAL_OK;
944 else
946 return HAL_BUSY;
951 * @brief Pauses the audio stream playing from the Media.
952 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
953 * the configuration information for I2S module
954 * @retval HAL status
956 HAL_StatusTypeDef HAL_I2S_DMAPause(I2S_HandleTypeDef *hi2s)
958 /* Process Locked */
959 __HAL_LOCK(hi2s);
961 if(hi2s->State == HAL_I2S_STATE_BUSY_TX)
963 /* Disable the I2S DMA Tx request */
964 hi2s->Instance->CR2 &= (uint32_t)(~SPI_CR2_TXDMAEN);
966 else if(hi2s->State == HAL_I2S_STATE_BUSY_RX)
968 /* Disable the I2S DMA Rx request */
969 hi2s->Instance->CR2 &= (uint32_t)(~SPI_CR2_RXDMAEN);
971 else if(hi2s->State == HAL_I2S_STATE_BUSY_TX_RX)
973 if((hi2s->Init.Mode == I2S_MODE_SLAVE_TX)||(hi2s->Init.Mode == I2S_MODE_MASTER_TX))
975 /* Disable the I2S DMA Tx request */
976 hi2s->Instance->CR2 &= (uint32_t)(~SPI_CR2_TXDMAEN);
978 else
980 /* Disable the I2S DMA Rx request */
981 hi2s->Instance->CR2 &= (uint32_t)(~SPI_CR2_RXDMAEN);
985 /* Process Unlocked */
986 __HAL_UNLOCK(hi2s);
988 return HAL_OK;
992 * @brief Resumes the audio stream playing from the Media.
993 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
994 * the configuration information for I2S module
995 * @retval HAL status
997 HAL_StatusTypeDef HAL_I2S_DMAResume(I2S_HandleTypeDef *hi2s)
999 /* Process Locked */
1000 __HAL_LOCK(hi2s);
1002 if(hi2s->State == HAL_I2S_STATE_BUSY_TX)
1004 /* Enable the I2S DMA Tx request */
1005 SET_BIT(hi2s->Instance->CR2, SPI_CR2_TXDMAEN);
1007 else if(hi2s->State == HAL_I2S_STATE_BUSY_RX)
1009 /* Enable the I2S DMA Rx request */
1010 SET_BIT(hi2s->Instance->CR2, SPI_CR2_RXDMAEN);
1013 /* If the I2S peripheral is still not enabled, enable it */
1014 if(HAL_IS_BIT_CLR(hi2s->Instance->I2SCFGR, SPI_I2SCFGR_I2SE))
1016 /* Enable I2S peripheral */
1017 __HAL_I2S_ENABLE(hi2s);
1020 /* Process Unlocked */
1021 __HAL_UNLOCK(hi2s);
1023 return HAL_OK;
1027 * @brief Stops the audio stream playing from the Media.
1028 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1029 * the configuration information for I2S module
1030 * @retval HAL status
1032 HAL_StatusTypeDef HAL_I2S_DMAStop(I2S_HandleTypeDef *hi2s)
1034 /* Process Locked */
1035 __HAL_LOCK(hi2s);
1037 /* Disable the I2S Tx/Rx DMA requests */
1038 CLEAR_BIT(hi2s->Instance->CR2, SPI_CR2_TXDMAEN);
1039 CLEAR_BIT(hi2s->Instance->CR2, SPI_CR2_RXDMAEN);
1041 /* Abort the I2S DMA Channel tx */
1042 if(hi2s->hdmatx != NULL)
1044 /* Disable the I2S DMA channel */
1045 __HAL_DMA_DISABLE(hi2s->hdmatx);
1046 HAL_DMA_Abort(hi2s->hdmatx);
1048 /* Abort the I2S DMA Channel rx */
1049 if(hi2s->hdmarx != NULL)
1051 /* Disable the I2S DMA channel */
1052 __HAL_DMA_DISABLE(hi2s->hdmarx);
1053 HAL_DMA_Abort(hi2s->hdmarx);
1056 /* Disable I2S peripheral */
1057 __HAL_I2S_DISABLE(hi2s);
1059 hi2s->State = HAL_I2S_STATE_READY;
1061 /* Process Unlocked */
1062 __HAL_UNLOCK(hi2s);
1064 return HAL_OK;
1068 * @brief This function handles I2S interrupt request.
1069 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1070 * the configuration information for I2S module
1071 * @retval HAL status
1073 void HAL_I2S_IRQHandler(I2S_HandleTypeDef *hi2s)
1075 __IO uint32_t i2ssr = hi2s->Instance->SR;
1077 if(hi2s->State == HAL_I2S_STATE_BUSY_RX)
1079 /* I2S in mode Receiver ----------------------------------------------------*/
1080 if(((i2ssr & I2S_FLAG_RXNE) == I2S_FLAG_RXNE) && (__HAL_I2S_GET_IT_SOURCE(hi2s, I2S_IT_RXNE) != RESET))
1082 I2S_Receive_IT(hi2s);
1085 /* I2S Overrun error interrupt occurred -------------------------------------*/
1086 if(((i2ssr & I2S_FLAG_OVR) == I2S_FLAG_OVR) && (__HAL_I2S_GET_IT_SOURCE(hi2s, I2S_IT_ERR) != RESET))
1088 /* Disable RXNE and ERR interrupt */
1089 __HAL_I2S_DISABLE_IT(hi2s, (I2S_IT_RXNE | I2S_IT_ERR));
1091 /* Set the I2S State ready */
1092 hi2s->State = HAL_I2S_STATE_READY;
1094 /* Set the error code and execute error callback*/
1095 hi2s->ErrorCode |= HAL_I2S_ERROR_OVR;
1096 HAL_I2S_ErrorCallback(hi2s);
1099 else if(hi2s->State == HAL_I2S_STATE_BUSY_TX)
1101 /* I2S in mode Transmitter ---------------------------------------------------*/
1102 if(((i2ssr & I2S_FLAG_TXE) == I2S_FLAG_TXE) && (__HAL_I2S_GET_IT_SOURCE(hi2s, I2S_IT_TXE) != RESET))
1104 I2S_Transmit_IT(hi2s);
1107 /* I2S Underrun error interrupt occurred ------------------------------------*/
1108 if(((i2ssr & I2S_FLAG_UDR) == I2S_FLAG_UDR) && (__HAL_I2S_GET_IT_SOURCE(hi2s, I2S_IT_ERR) != RESET))
1110 /* Disable TXE and ERR interrupt */
1111 __HAL_I2S_DISABLE_IT(hi2s, (I2S_IT_TXE | I2S_IT_ERR));
1113 /* Set the I2S State ready */
1114 hi2s->State = HAL_I2S_STATE_READY;
1116 /* Set the error code and execute error callback*/
1117 hi2s->ErrorCode |= HAL_I2S_ERROR_UDR;
1118 HAL_I2S_ErrorCallback(hi2s);
1124 * @}
1128 * @}
1131 /** @addtogroup I2S_Private_Functions I2S Private Functions
1132 * @{
1135 * @brief This function handles I2S Communication Timeout.
1136 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1137 * the configuration information for I2S module
1138 * @param Flag: Flag checked
1139 * @param State: Value of the flag expected
1140 * @param Timeout: Duration of the timeout
1141 * @retval HAL status
1143 static HAL_StatusTypeDef I2S_WaitFlagStateUntilTimeout(I2S_HandleTypeDef *hi2s, uint32_t Flag,
1144 uint32_t State, uint32_t Timeout)
1146 uint32_t tickstart = 0;
1148 /* Get tick */
1149 tickstart = HAL_GetTick();
1151 /* Wait until flag is set */
1152 if(State == RESET)
1154 while(__HAL_I2S_GET_FLAG(hi2s, Flag) == RESET)
1156 if(Timeout != HAL_MAX_DELAY)
1158 if((Timeout == 0)||((HAL_GetTick() - tickstart ) > Timeout))
1160 /* Set the I2S State ready */
1161 hi2s->State= HAL_I2S_STATE_READY;
1163 /* Process Unlocked */
1164 __HAL_UNLOCK(hi2s);
1166 return HAL_TIMEOUT;
1171 else
1173 while(__HAL_I2S_GET_FLAG(hi2s, Flag) != RESET)
1175 if(Timeout != HAL_MAX_DELAY)
1177 if((Timeout == 0)||((HAL_GetTick() - tickstart ) > Timeout))
1179 /* Set the I2S State ready */
1180 hi2s->State= HAL_I2S_STATE_READY;
1182 /* Process Unlocked */
1183 __HAL_UNLOCK(hi2s);
1185 return HAL_TIMEOUT;
1190 return HAL_OK;
1193 * @}
1196 /** @addtogroup I2S_Exported_Functions I2S Exported Functions
1197 * @{
1200 /** @addtogroup I2S_Exported_Functions_Group2 Input and Output operation functions
1201 * @{
1204 * @brief Tx Transfer Half completed callbacks
1205 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1206 * the configuration information for I2S module
1207 * @retval None
1209 __weak void HAL_I2S_TxHalfCpltCallback(I2S_HandleTypeDef *hi2s)
1211 /* Prevent unused argument(s) compilation warning */
1212 UNUSED(hi2s);
1214 /* NOTE : This function Should not be modified, when the callback is needed,
1215 the HAL_I2S_TxHalfCpltCallback could be implemented in the user file
1220 * @brief Tx Transfer completed callbacks
1221 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1222 * the configuration information for I2S module
1223 * @retval None
1225 __weak void HAL_I2S_TxCpltCallback(I2S_HandleTypeDef *hi2s)
1227 /* Prevent unused argument(s) compilation warning */
1228 UNUSED(hi2s);
1230 /* NOTE : This function Should not be modified, when the callback is needed,
1231 the HAL_I2S_TxCpltCallback could be implemented in the user file
1236 * @brief Rx Transfer half completed callbacks
1237 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1238 * the configuration information for I2S module
1239 * @retval None
1241 __weak void HAL_I2S_RxHalfCpltCallback(I2S_HandleTypeDef *hi2s)
1243 /* Prevent unused argument(s) compilation warning */
1244 UNUSED(hi2s);
1246 /* NOTE : This function Should not be modified, when the callback is needed,
1247 the HAL_I2S_RxCpltCallback could be implemented in the user file
1252 * @brief Rx Transfer completed callbacks
1253 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1254 * the configuration information for I2S module
1255 * @retval None
1257 __weak void HAL_I2S_RxCpltCallback(I2S_HandleTypeDef *hi2s)
1259 /* Prevent unused argument(s) compilation warning */
1260 UNUSED(hi2s);
1262 /* NOTE : This function Should not be modified, when the callback is needed,
1263 the HAL_I2S_RxCpltCallback could be implemented in the user file
1268 * @brief I2S error callbacks
1269 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1270 * the configuration information for I2S module
1271 * @retval None
1273 __weak void HAL_I2S_ErrorCallback(I2S_HandleTypeDef *hi2s)
1275 /* Prevent unused argument(s) compilation warning */
1276 UNUSED(hi2s);
1278 /* NOTE : This function Should not be modified, when the callback is needed,
1279 the HAL_I2S_ErrorCallback could be implemented in the user file
1284 * @}
1287 /** @defgroup I2S_Exported_Functions_Group3 Peripheral State and Errors functions
1288 * @brief Peripheral State functions
1290 @verbatim
1291 ===============================================================================
1292 ##### Peripheral State and Errors functions #####
1293 ===============================================================================
1294 [..]
1295 This subsection permits to get in run-time the status of the peripheral
1296 and the data flow.
1298 @endverbatim
1299 * @{
1303 * @brief Return the I2S state
1304 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1305 * the configuration information for I2S module
1306 * @retval HAL state
1308 HAL_I2S_StateTypeDef HAL_I2S_GetState(I2S_HandleTypeDef *hi2s)
1310 return hi2s->State;
1314 * @brief Return the I2S error code
1315 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1316 * the configuration information for I2S module
1317 * @retval I2S Error Code
1319 uint32_t HAL_I2S_GetError(I2S_HandleTypeDef *hi2s)
1321 return hi2s->ErrorCode;
1324 * @}
1328 * @}
1332 * @brief Get I2S Input Clock based on I2S source clock selection
1333 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1334 * the configuration information for I2S module.
1335 * @retval I2S Clock Input
1337 static uint32_t I2S_GetClockFreq(I2S_HandleTypeDef *hi2s)
1339 uint32_t tmpreg = 0;
1340 /* This variable used to store the VCO Input (value in Hz) */
1341 uint32_t vcoinput = 0;
1342 /* This variable used to store the I2S_CK_x (value in Hz) */
1343 uint32_t i2sclocksource = 0;
1345 /* Configure I2S Clock based on I2S source clock selection */
1347 /* I2S_CLK_x : I2S Block Clock configuration for different clock sources selected */
1348 switch(hi2s->Init.ClockSource)
1350 case I2S_CLOCK_PLL :
1352 /* Configure the PLLI2S division factor */
1353 /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */
1354 if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSI)
1356 /* In Case the PLL Source is HSI (Internal Clock) */
1357 vcoinput = (HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM));
1359 else
1361 /* In Case the PLL Source is HSE (External Clock) */
1362 vcoinput = ((HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)));
1365 /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */
1366 /* I2S_CLK(first level) = PLLI2S_VCO Output/PLLI2SR */
1367 tmpreg = (RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28;
1368 i2sclocksource = (vcoinput * ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6))/(tmpreg);
1370 break;
1372 case I2S_CLOCK_EXTERNAL :
1374 i2sclocksource = EXTERNAL_CLOCK_VALUE;
1375 break;
1377 default :
1379 break;
1383 /* the return result is the value of I2S clock */
1384 return i2sclocksource;
1387 /** @addtogroup I2S_Private_Functions I2S Private Functions
1388 * @{
1391 * @brief DMA I2S transmit process complete callback
1392 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1393 * the configuration information for the specified DMA module.
1394 * @retval None
1396 static void I2S_DMATxCplt(DMA_HandleTypeDef *hdma)
1398 I2S_HandleTypeDef* hi2s = (I2S_HandleTypeDef*)((DMA_HandleTypeDef*)hdma)->Parent;
1400 if((hdma->Instance->CR & DMA_SxCR_CIRC) == 0)
1402 hi2s->TxXferCount = 0;
1404 /* Disable Tx DMA Request */
1405 hi2s->Instance->CR2 &= (uint32_t)(~SPI_CR2_TXDMAEN);
1407 if(hi2s->State == HAL_I2S_STATE_BUSY_TX_RX)
1409 if(hi2s->RxXferCount == 0)
1411 hi2s->State = HAL_I2S_STATE_READY;
1414 else
1416 hi2s->State = HAL_I2S_STATE_READY;
1419 HAL_I2S_TxCpltCallback(hi2s);
1423 * @brief DMA I2S transmit process half complete callback
1424 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1425 * the configuration information for the specified DMA module.
1426 * @retval None
1428 static void I2S_DMATxHalfCplt(DMA_HandleTypeDef *hdma)
1430 I2S_HandleTypeDef* hi2s = (I2S_HandleTypeDef*)((DMA_HandleTypeDef*)hdma)->Parent;
1432 HAL_I2S_TxHalfCpltCallback(hi2s);
1436 * @brief DMA I2S receive process complete callback
1437 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1438 * the configuration information for the specified DMA module.
1439 * @retval None
1441 static void I2S_DMARxCplt(DMA_HandleTypeDef *hdma)
1443 I2S_HandleTypeDef* hi2s = (I2S_HandleTypeDef*)((DMA_HandleTypeDef*)hdma)->Parent;
1445 if((hdma->Instance->CR & DMA_SxCR_CIRC) == 0)
1447 /* Disable Rx DMA Request */
1448 hi2s->Instance->CR2 &= (uint32_t)(~SPI_CR2_RXDMAEN);
1450 hi2s->RxXferCount = 0;
1451 if(hi2s->State == HAL_I2S_STATE_BUSY_TX_RX)
1453 if(hi2s->TxXferCount == 0)
1455 hi2s->State = HAL_I2S_STATE_READY;
1458 else
1460 hi2s->State = HAL_I2S_STATE_READY;
1463 HAL_I2S_RxCpltCallback(hi2s);
1467 * @brief DMA I2S receive process half complete callback
1468 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1469 * the configuration information for the specified DMA module.
1470 * @retval None
1472 static void I2S_DMARxHalfCplt(DMA_HandleTypeDef *hdma)
1474 I2S_HandleTypeDef* hi2s = (I2S_HandleTypeDef*)((DMA_HandleTypeDef*)hdma)->Parent;
1476 HAL_I2S_RxHalfCpltCallback(hi2s);
1480 * @brief DMA I2S communication error callback
1481 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1482 * the configuration information for the specified DMA module.
1483 * @retval None
1485 static void I2S_DMAError(DMA_HandleTypeDef *hdma)
1487 I2S_HandleTypeDef* hi2s = ( I2S_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent;
1489 /* Disable Rx and Tx DMA Request */
1490 hi2s->Instance->CR2 &= (uint32_t)(~(SPI_CR2_RXDMAEN | SPI_CR2_TXDMAEN));
1491 hi2s->TxXferCount = 0;
1492 hi2s->RxXferCount = 0;
1494 hi2s->State= HAL_I2S_STATE_READY;
1496 /* Set the error code and execute error callback*/
1497 hi2s->ErrorCode |= HAL_I2S_ERROR_DMA;
1498 HAL_I2S_ErrorCallback(hi2s);
1502 * @brief Transmit an amount of data in non-blocking mode with Interrupt
1503 * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains
1504 * the configuration information for I2S module
1505 * @retval None
1507 static void I2S_Transmit_IT(I2S_HandleTypeDef *hi2s)
1509 /* Transmit data */
1510 hi2s->Instance->DR = (*hi2s->pTxBuffPtr++);
1511 hi2s->TxXferCount--;
1513 if(hi2s->TxXferCount == 0)
1515 /* Disable TXE and ERR interrupt */
1516 __HAL_I2S_DISABLE_IT(hi2s, (I2S_IT_TXE | I2S_IT_ERR));
1518 hi2s->State = HAL_I2S_STATE_READY;
1519 HAL_I2S_TxCpltCallback(hi2s);
1524 * @brief Receive an amount of data in non-blocking mode with Interrupt
1525 * @param hi2s: I2S handle
1526 * @retval None
1528 static void I2S_Receive_IT(I2S_HandleTypeDef *hi2s)
1530 /* Receive data */
1531 (*hi2s->pRxBuffPtr++) = hi2s->Instance->DR;
1532 hi2s->RxXferCount--;
1534 if(hi2s->RxXferCount == 0)
1536 /* Disable RXNE and ERR interrupt */
1537 __HAL_I2S_DISABLE_IT(hi2s, (I2S_IT_RXNE | I2S_IT_ERR));
1539 hi2s->State = HAL_I2S_STATE_READY;
1540 HAL_I2S_RxCpltCallback(hi2s);
1544 * @}
1547 #endif /* HAL_I2S_MODULE_ENABLED */
1549 * @}
1553 * @}
1556 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/