2 ******************************************************************************
3 * @file stm32f7xx_hal_sai.c
4 * @author MCD Application Team
7 * @brief SAI HAL module driver.
8 * This file provides firmware functions to manage the following
9 * functionalities of the Serial Audio Interface (SAI) peripheral:
10 * + Initialization/de-initialization functions
11 * + I/O operation functions
12 * + Peripheral Control functions
13 * + Peripheral State functions
16 ==============================================================================
17 ##### How to use this driver #####
18 ==============================================================================
21 The SAI HAL driver can be used as follows:
23 (#) Declare a SAI_HandleTypeDef handle structure (eg. SAI_HandleTypeDef hsai).
24 (#) Initialize the SAI low level resources by implementing the HAL_SAI_MspInit() API:
25 (##) Enable the SAI interface clock.
26 (##) SAI pins configuration:
27 (+++) Enable the clock for the SAI GPIOs.
28 (+++) Configure these SAI pins as alternate function pull-up.
29 (##) NVIC configuration if you need to use interrupt process (HAL_SAI_Transmit_IT()
30 and HAL_SAI_Receive_IT() APIs):
31 (+++) Configure the SAI interrupt priority.
32 (+++) Enable the NVIC SAI IRQ handle.
34 (##) DMA Configuration if you need to use DMA process (HAL_SAI_Transmit_DMA()
35 and HAL_SAI_Receive_DMA() APIs):
36 (+++) Declare a DMA handle structure for the Tx/Rx stream.
37 (+++) Enable the DMAx interface clock.
38 (+++) Configure the declared DMA handle structure with the required Tx/Rx parameters.
39 (+++) Configure the DMA Tx/Rx Stream.
40 (+++) Associate the initialized DMA handle to the SAI DMA Tx/Rx handle.
41 (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on the
44 (#) The initialization can be done by two ways
45 (##) Expert mode : Initialize the structures Init, FrameInit and SlotInit and call HAL_SAI_Init().
46 (##) Simplified mode : Initialize the high part of Init Structure and call HAL_SAI_InitProtocol().
49 (@) The specific SAI interrupts (FIFO request and Overrun underrun interrupt)
50 will be managed using the macros __HAL_SAI_ENABLE_IT() and __HAL_SAI_DISABLE_IT()
51 inside the transmit and receive process.
53 (@) Make sure that either:
54 (+@) I2S PLL is configured or
55 (+@) SAI PLL is configured or
56 (+@) External clock source is configured after setting correctly
57 the define constant EXTERNAL_CLOCK_VALUE in the stm32f7xx_hal_conf.h file.
59 (@) In master Tx mode: enabling the audio block immediately generates the bit clock
60 for the external slaves even if there is no data in the FIFO, However FS signal
61 generation is conditioned by the presence of data in the FIFO.
64 (@) In master Rx mode: enabling the audio block immediately generates the bit clock
65 and FS signal for the external slaves.
68 (@) It is mandatory to respect the following conditions in order to avoid bad SAI behavior:
69 (+@) First bit Offset <= (SLOT size - Data size)
70 (+@) Data size <= SLOT size
71 (+@) Number of SLOT x SLOT size = Frame length
72 (+@) The number of slots should be even when SAI_FS_CHANNEL_IDENTIFICATION is selected.
75 Three operation modes are available within this driver :
77 *** Polling mode IO operation ***
78 =================================
80 (+) Send an amount of data in blocking mode using HAL_SAI_Transmit()
81 (+) Receive an amount of data in blocking mode using HAL_SAI_Receive()
83 *** Interrupt mode IO operation ***
84 ===================================
86 (+) Send an amount of data in non-blocking mode using HAL_SAI_Transmit_IT()
87 (+) At transmission end of transfer HAL_SAI_TxCpltCallback() is executed and user can
88 add his own code by customization of function pointer HAL_SAI_TxCpltCallback()
89 (+) Receive an amount of data in non-blocking mode using HAL_SAI_Receive_IT()
90 (+) At reception end of transfer HAL_SAI_RxCpltCallback() is executed and user can
91 add his own code by customization of function pointer HAL_SAI_RxCpltCallback()
92 (+) In case of flag error, HAL_SAI_ErrorCallback() function is executed and user can
93 add his own code by customization of function pointer HAL_SAI_ErrorCallback()
95 *** DMA mode IO operation ***
96 =============================
98 (+) Send an amount of data in non-blocking mode (DMA) using HAL_SAI_Transmit_DMA()
99 (+) At transmission end of transfer HAL_SAI_TxCpltCallback() is executed and user can
100 add his own code by customization of function pointer HAL_SAI_TxCpltCallback()
101 (+) Receive an amount of data in non-blocking mode (DMA) using HAL_SAI_Receive_DMA()
102 (+) At reception end of transfer HAL_SAI_RxCpltCallback() is executed and user can
103 add his own code by customization of function pointer HAL_SAI_RxCpltCallback()
104 (+) In case of flag error, HAL_SAI_ErrorCallback() function is executed and user can
105 add his own code by customization of function pointer HAL_SAI_ErrorCallback()
106 (+) Pause the DMA Transfer using HAL_SAI_DMAPause()
107 (+) Resume the DMA Transfer using HAL_SAI_DMAResume()
108 (+) Stop the DMA Transfer using HAL_SAI_DMAStop()
110 *** SAI HAL driver additional function list ***
111 ===============================================
113 Below the list the others API available SAI HAL driver :
115 (+) HAL_SAI_EnableTxMuteMode(): Enable the mute in tx mode
116 (+) HAL_SAI_DisableTxMuteMode(): Disable the mute in tx mode
117 (+) HAL_SAI_EnableRxMuteMode(): Enable the mute in Rx mode
118 (+) HAL_SAI_DisableRxMuteMode(): Disable the mute in Rx mode
119 (+) HAL_SAI_FlushRxFifo(): Flush the rx fifo.
120 (+) HAL_SAI_Abort(): Abort the current transfer
122 *** SAI HAL driver macros list ***
123 ==================================
125 Below the list of most used macros in SAI HAL driver :
127 (+) __HAL_SAI_ENABLE(): Enable the SAI peripheral
128 (+) __HAL_SAI_DISABLE(): Disable the SAI peripheral
129 (+) __HAL_SAI_ENABLE_IT(): Enable the specified SAI interrupts
130 (+) __HAL_SAI_DISABLE_IT(): Disable the specified SAI interrupts
131 (+) __HAL_SAI_GET_IT_SOURCE(): Check if the specified SAI interrupt source is
133 (+) __HAL_SAI_GET_FLAG(): Check whether the specified SAI flag is set or not
136 ******************************************************************************
139 * <h2><center>© COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
141 * Redistribution and use in source and binary forms, with or without modification,
142 * are permitted provided that the following conditions are met:
143 * 1. Redistributions of source code must retain the above copyright notice,
144 * this list of conditions and the following disclaimer.
145 * 2. Redistributions in binary form must reproduce the above copyright notice,
146 * this list of conditions and the following disclaimer in the documentation
147 * and/or other materials provided with the distribution.
148 * 3. Neither the name of STMicroelectronics nor the names of its contributors
149 * may be used to endorse or promote products derived from this software
150 * without specific prior written permission.
152 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
153 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
154 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
155 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
156 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
157 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
158 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
159 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
160 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
161 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
163 ******************************************************************************
166 /* Includes ------------------------------------------------------------------*/
167 #include "stm32f7xx_hal.h"
169 /** @addtogroup STM32F7xx_HAL_Driver
173 /** @defgroup SAI SAI
174 * @brief SAI HAL module driver
178 #ifdef HAL_SAI_MODULE_ENABLED
180 /* Private typedef -----------------------------------------------------------*/
182 /** @defgroup SAI_Private_Typedefs SAI Private Typedefs
193 /* Private define ------------------------------------------------------------*/
195 /** @defgroup SAI_Private_Constants SAI Private Constants
198 #define SAI_FIFO_SIZE 8
199 #define SAI_DEFAULT_TIMEOUT 4 /* 4ms */
200 #define SAI_xCR2_MUTECNT_OFFSET POSITION_VAL(SAI_xCR2_MUTECNT)
205 /* Private macro -------------------------------------------------------------*/
206 /* Private variables ---------------------------------------------------------*/
207 /* Private function prototypes -----------------------------------------------*/
209 /** @defgroup SAI_Private_Functions SAI Private Functions
212 static void SAI_FillFifo(SAI_HandleTypeDef
*hsai
);
213 static uint32_t SAI_InterruptFlag(SAI_HandleTypeDef
*hsai
, uint32_t mode
);
214 static HAL_StatusTypeDef
SAI_InitI2S(SAI_HandleTypeDef
*hsai
, uint32_t protocol
, uint32_t datasize
, uint32_t nbslot
);
215 static HAL_StatusTypeDef
SAI_InitPCM(SAI_HandleTypeDef
*hsai
, uint32_t protocol
, uint32_t datasize
, uint32_t nbslot
);
217 static HAL_StatusTypeDef
SAI_Disable(SAI_HandleTypeDef
*hsai
);
218 static void SAI_Transmit_IT8Bit(SAI_HandleTypeDef
*hsai
);
219 static void SAI_Transmit_IT16Bit(SAI_HandleTypeDef
*hsai
);
220 static void SAI_Transmit_IT32Bit(SAI_HandleTypeDef
*hsai
);
221 static void SAI_Receive_IT8Bit(SAI_HandleTypeDef
*hsai
);
222 static void SAI_Receive_IT16Bit(SAI_HandleTypeDef
*hsai
);
223 static void SAI_Receive_IT32Bit(SAI_HandleTypeDef
*hsai
);
225 static void SAI_DMATxCplt(DMA_HandleTypeDef
*hdma
);
226 static void SAI_DMATxHalfCplt(DMA_HandleTypeDef
*hdma
);
227 static void SAI_DMARxCplt(DMA_HandleTypeDef
*hdma
);
228 static void SAI_DMARxHalfCplt(DMA_HandleTypeDef
*hdma
);
229 static void SAI_DMAError(DMA_HandleTypeDef
*hdma
);
230 static void SAI_DMAAbort(DMA_HandleTypeDef
*hdma
);
235 /* Exported functions ---------------------------------------------------------*/
237 /** @defgroup SAI_Exported_Functions SAI Exported Functions
241 /** @defgroup SAI_Exported_Functions_Group1 Initialization and de-initialization functions
242 * @brief Initialization and Configuration functions
245 ===============================================================================
246 ##### Initialization and de-initialization functions #####
247 ===============================================================================
248 [..] This subsection provides a set of functions allowing to initialize and
249 de-initialize the SAIx peripheral:
251 (+) User must implement HAL_SAI_MspInit() function in which he configures
252 all related peripherals resources (CLOCK, GPIO, DMA, IT and NVIC ).
254 (+) Call the function HAL_SAI_Init() to configure the selected device with
255 the selected configuration:
256 (++) Mode (Master/slave TX/RX)
265 (+) Call the function HAL_SAI_DeInit() to restore the default configuration
266 of the selected SAI peripheral.
273 * @brief Initialize the structure FrameInit, SlotInit and the low part of
274 * Init according to the specified parameters and call the function
275 * HAL_SAI_Init to initialize the SAI block.
276 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
277 * the configuration information for SAI module.
278 * @param protocol: one of the supported protocol @ref SAI_Protocol
279 * @param datasize: one of the supported datasize @ref SAI_Protocol_DataSize
280 * the configuration information for SAI module.
281 * @param nbslot: Number of slot.
284 HAL_StatusTypeDef
HAL_SAI_InitProtocol(SAI_HandleTypeDef
*hsai
, uint32_t protocol
, uint32_t datasize
, uint32_t nbslot
)
286 HAL_StatusTypeDef status
= HAL_OK
;
288 /* Check the parameters */
289 assert_param(IS_SAI_SUPPORTED_PROTOCOL(protocol
));
290 assert_param(IS_SAI_PROTOCOL_DATASIZE(datasize
));
294 case SAI_I2S_STANDARD
:
295 case SAI_I2S_MSBJUSTIFIED
:
296 case SAI_I2S_LSBJUSTIFIED
:
297 status
= SAI_InitI2S(hsai
, protocol
, datasize
, nbslot
);
301 status
= SAI_InitPCM(hsai
, protocol
, datasize
, nbslot
);
310 status
= HAL_SAI_Init(hsai
);
317 * @brief Initialize the SAI according to the specified parameters.
318 * in the SAI_InitTypeDef structure and initialize the associated handle.
319 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
320 * the configuration information for SAI module.
323 HAL_StatusTypeDef
HAL_SAI_Init(SAI_HandleTypeDef
*hsai
)
325 uint32_t tmpregisterGCR
= 0;
326 uint32_t ckstr_bits
= 0;
327 uint32_t syncen_bits
= 0;
329 /* Check the SAI handle allocation */
335 /* check the instance */
336 assert_param(IS_SAI_ALL_INSTANCE(hsai
->Instance
));
338 /* Check the SAI Block parameters */
339 assert_param(IS_SAI_AUDIO_FREQUENCY(hsai
->Init
.AudioFrequency
));
340 assert_param(IS_SAI_BLOCK_PROTOCOL(hsai
->Init
.Protocol
));
341 assert_param(IS_SAI_BLOCK_MODE(hsai
->Init
.AudioMode
));
342 assert_param(IS_SAI_BLOCK_DATASIZE(hsai
->Init
.DataSize
));
343 assert_param(IS_SAI_BLOCK_FIRST_BIT(hsai
->Init
.FirstBit
));
344 assert_param(IS_SAI_BLOCK_CLOCK_STROBING(hsai
->Init
.ClockStrobing
));
345 assert_param(IS_SAI_BLOCK_SYNCHRO(hsai
->Init
.Synchro
));
346 assert_param(IS_SAI_BLOCK_OUTPUT_DRIVE(hsai
->Init
.OutputDrive
));
347 assert_param(IS_SAI_BLOCK_NODIVIDER(hsai
->Init
.NoDivider
));
348 assert_param(IS_SAI_BLOCK_FIFO_THRESHOLD(hsai
->Init
.FIFOThreshold
));
349 assert_param(IS_SAI_MONO_STEREO_MODE(hsai
->Init
.MonoStereoMode
));
350 assert_param(IS_SAI_BLOCK_COMPANDING_MODE(hsai
->Init
.CompandingMode
));
351 assert_param(IS_SAI_BLOCK_TRISTATE_MANAGEMENT(hsai
->Init
.TriState
));
352 assert_param(IS_SAI_BLOCK_SYNCEXT(hsai
->Init
.SynchroExt
));
354 /* Check the SAI Block Frame parameters */
355 assert_param(IS_SAI_BLOCK_FRAME_LENGTH(hsai
->FrameInit
.FrameLength
));
356 assert_param(IS_SAI_BLOCK_ACTIVE_FRAME(hsai
->FrameInit
.ActiveFrameLength
));
357 assert_param(IS_SAI_BLOCK_FS_DEFINITION(hsai
->FrameInit
.FSDefinition
));
358 assert_param(IS_SAI_BLOCK_FS_POLARITY(hsai
->FrameInit
.FSPolarity
));
359 assert_param(IS_SAI_BLOCK_FS_OFFSET(hsai
->FrameInit
.FSOffset
));
361 /* Check the SAI Block Slot parameters */
362 assert_param(IS_SAI_BLOCK_FIRSTBIT_OFFSET(hsai
->SlotInit
.FirstBitOffset
));
363 assert_param(IS_SAI_BLOCK_SLOT_SIZE(hsai
->SlotInit
.SlotSize
));
364 assert_param(IS_SAI_BLOCK_SLOT_NUMBER(hsai
->SlotInit
.SlotNumber
));
365 assert_param(IS_SAI_SLOT_ACTIVE(hsai
->SlotInit
.SlotActive
));
367 if(hsai
->State
== HAL_SAI_STATE_RESET
)
369 /* Allocate lock resource and initialize it */
370 hsai
->Lock
= HAL_UNLOCKED
;
372 /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */
373 HAL_SAI_MspInit(hsai
);
376 hsai
->State
= HAL_SAI_STATE_BUSY
;
378 /* Disable the selected SAI peripheral */
381 /* SAI Block Synchro Configuration -----------------------------------------*/
382 /* This setting must be done with both audio block (A & B) disabled */
383 switch(hsai
->Init
.SynchroExt
)
385 case SAI_SYNCEXT_DISABLE
:
388 case SAI_SYNCEXT_OUTBLOCKA_ENABLE
:
389 tmpregisterGCR
= SAI_GCR_SYNCOUT_0
;
391 case SAI_SYNCEXT_OUTBLOCKB_ENABLE
:
392 tmpregisterGCR
= SAI_GCR_SYNCOUT_1
;
398 switch(hsai
->Init
.Synchro
)
400 case SAI_ASYNCHRONOUS
:
405 case SAI_SYNCHRONOUS
:
407 syncen_bits
= SAI_xCR1_SYNCEN_0
;
410 case SAI_SYNCHRONOUS_EXT_SAI1
:
412 syncen_bits
= SAI_xCR1_SYNCEN_1
;
415 case SAI_SYNCHRONOUS_EXT_SAI2
:
417 syncen_bits
= SAI_xCR1_SYNCEN_1
;
418 tmpregisterGCR
|= SAI_GCR_SYNCIN_0
;
425 if((hsai
->Instance
== SAI1_Block_A
) || (hsai
->Instance
== SAI1_Block_B
))
427 SAI1
->GCR
= tmpregisterGCR
;
431 SAI2
->GCR
= tmpregisterGCR
;
434 if(hsai
->Init
.AudioFrequency
!= SAI_AUDIO_FREQUENCY_MCKDIV
)
439 if((hsai
->Instance
== SAI1_Block_A
) || (hsai
->Instance
== SAI1_Block_B
))
441 freq
= HAL_RCCEx_GetPeriphCLKFreq(RCC_PERIPHCLK_SAI1
);
443 if((hsai
->Instance
== SAI2_Block_A
) || (hsai
->Instance
== SAI2_Block_B
))
445 freq
= HAL_RCCEx_GetPeriphCLKFreq(RCC_PERIPHCLK_SAI2
);
448 /* Configure Master Clock using the following formula :
449 MCLK_x = SAI_CK_x / (MCKDIV[3:0] * 2) with MCLK_x = 256 * FS
450 FS = SAI_CK_x / (MCKDIV[3:0] * 2) * 256
451 MCKDIV[3:0] = SAI_CK_x / FS * 512 */
452 /* (freq x 10) to keep Significant digits */
453 tmpval
= (freq
* 10) / (hsai
->Init
.AudioFrequency
* 2 * 256);
454 hsai
->Init
.Mckdiv
= tmpval
/ 10;
456 /* Round result to the nearest integer */
457 if((tmpval
% 10) > 8)
459 hsai
->Init
.Mckdiv
+= 1;
463 /* Compute CKSTR bits of SAI CR1 according ClockStrobing and AudioMode */
464 if((hsai
->Init
.AudioMode
== SAI_MODEMASTER_TX
) || (hsai
->Init
.AudioMode
== SAI_MODESLAVE_TX
))
466 ckstr_bits
= (hsai
->Init
.ClockStrobing
== SAI_CLOCKSTROBING_RISINGEDGE
) ? 0 : SAI_xCR1_CKSTR
;
470 ckstr_bits
= (hsai
->Init
.ClockStrobing
== SAI_CLOCKSTROBING_RISINGEDGE
) ? SAI_xCR1_CKSTR
: 0;
473 /* SAI Block Configuration -------------------------------------------------*/
474 /* SAI CR1 Configuration */
475 hsai
->Instance
->CR1
&=~(SAI_xCR1_MODE
| SAI_xCR1_PRTCFG
| SAI_xCR1_DS
| \
476 SAI_xCR1_LSBFIRST
| SAI_xCR1_CKSTR
| SAI_xCR1_SYNCEN
|\
477 SAI_xCR1_MONO
| SAI_xCR1_OUTDRIV
| SAI_xCR1_DMAEN
| \
478 SAI_xCR1_NODIV
| SAI_xCR1_MCKDIV
);
480 hsai
->Instance
->CR1
|=(hsai
->Init
.AudioMode
| hsai
->Init
.Protocol
| \
481 hsai
->Init
.DataSize
| hsai
->Init
.FirstBit
| \
482 ckstr_bits
| syncen_bits
| \
483 hsai
->Init
.MonoStereoMode
| hsai
->Init
.OutputDrive
| \
484 hsai
->Init
.NoDivider
| (hsai
->Init
.Mckdiv
<< 20));
486 /* SAI CR2 Configuration */
487 hsai
->Instance
->CR2
&= ~(SAI_xCR2_FTH
| SAI_xCR2_FFLUSH
| SAI_xCR2_COMP
| SAI_xCR2_CPL
);
488 hsai
->Instance
->CR2
|= (hsai
->Init
.FIFOThreshold
| hsai
->Init
.CompandingMode
| hsai
->Init
.TriState
);
490 /* SAI Frame Configuration -----------------------------------------*/
491 hsai
->Instance
->FRCR
&=(~(SAI_xFRCR_FRL
| SAI_xFRCR_FSALL
| SAI_xFRCR_FSDEF
| \
492 SAI_xFRCR_FSPOL
| SAI_xFRCR_FSOFF
));
493 hsai
->Instance
->FRCR
|=((hsai
->FrameInit
.FrameLength
- 1) |
494 hsai
->FrameInit
.FSOffset
|
495 hsai
->FrameInit
.FSDefinition
|
496 hsai
->FrameInit
.FSPolarity
|
497 ((hsai
->FrameInit
.ActiveFrameLength
- 1) << 8));
499 /* SAI Block_x SLOT Configuration ------------------------------------------*/
500 /* This register has no meaning in AC 97 and SPDIF audio protocol */
501 hsai
->Instance
->SLOTR
&= (~(SAI_xSLOTR_FBOFF
| SAI_xSLOTR_SLOTSZ
| \
502 SAI_xSLOTR_NBSLOT
| SAI_xSLOTR_SLOTEN
));
504 hsai
->Instance
->SLOTR
|= hsai
->SlotInit
.FirstBitOffset
| hsai
->SlotInit
.SlotSize
505 | (hsai
->SlotInit
.SlotActive
<< 16) | ((hsai
->SlotInit
.SlotNumber
- 1) << 8);
507 /* Initialize the error code */
508 hsai
->ErrorCode
= HAL_SAI_ERROR_NONE
;
510 /* Initialize the SAI state */
511 hsai
->State
= HAL_SAI_STATE_READY
;
520 * @brief DeInitialize the SAI peripheral.
521 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
522 * the configuration information for SAI module.
525 HAL_StatusTypeDef
HAL_SAI_DeInit(SAI_HandleTypeDef
*hsai
)
527 /* Check the SAI handle allocation */
533 hsai
->State
= HAL_SAI_STATE_BUSY
;
535 /* Disabled All interrupt and clear all the flag */
536 hsai
->Instance
->IMR
= 0;
537 hsai
->Instance
->CLRFR
= 0xFFFFFFFFU
;
539 /* Disable the SAI */
543 SET_BIT(hsai
->Instance
->CR2
, SAI_xCR2_FFLUSH
);
545 /* DeInit the low level hardware: GPIO, CLOCK, NVIC and DMA */
546 HAL_SAI_MspDeInit(hsai
);
548 /* Initialize the error code */
549 hsai
->ErrorCode
= HAL_SAI_ERROR_NONE
;
551 /* Initialize the SAI state */
552 hsai
->State
= HAL_SAI_STATE_RESET
;
561 * @brief Initialize the SAI MSP.
562 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
563 * the configuration information for SAI module.
566 __weak
void HAL_SAI_MspInit(SAI_HandleTypeDef
*hsai
)
568 /* Prevent unused argument(s) compilation warning */
571 /* NOTE : This function should not be modified, when the callback is needed,
572 the HAL_SAI_MspInit could be implemented in the user file
577 * @brief DeInitialize the SAI MSP.
578 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
579 * the configuration information for SAI module.
582 __weak
void HAL_SAI_MspDeInit(SAI_HandleTypeDef
*hsai
)
584 /* Prevent unused argument(s) compilation warning */
587 /* NOTE : This function should not be modified, when the callback is needed,
588 the HAL_SAI_MspDeInit could be implemented in the user file
596 /** @defgroup SAI_Exported_Functions_Group2 IO operation functions
597 * @brief Data transfers functions
600 ==============================================================================
601 ##### IO operation functions #####
602 ==============================================================================
604 This subsection provides a set of functions allowing to manage the SAI data
607 (+) There are two modes of transfer:
608 (++) Blocking mode : The communication is performed in the polling mode.
609 The status of all data processing is returned by the same function
610 after finishing transfer.
611 (++) No-Blocking mode : The communication is performed using Interrupts
612 or DMA. These functions return the status of the transfer startup.
613 The end of the data processing will be indicated through the
614 dedicated SAI IRQ when using Interrupt mode or the DMA IRQ when
617 (+) Blocking mode functions are :
618 (++) HAL_SAI_Transmit()
619 (++) HAL_SAI_Receive()
620 (++) HAL_SAI_TransmitReceive()
622 (+) Non Blocking mode functions with Interrupt are :
623 (++) HAL_SAI_Transmit_IT()
624 (++) HAL_SAI_Receive_IT()
625 (++) HAL_SAI_TransmitReceive_IT()
627 (+) Non Blocking mode functions with DMA are :
628 (++) HAL_SAI_Transmit_DMA()
629 (++) HAL_SAI_Receive_DMA()
630 (++) HAL_SAI_TransmitReceive_DMA()
632 (+) A set of Transfer Complete Callbacks are provided in non Blocking mode:
633 (++) HAL_SAI_TxCpltCallback()
634 (++) HAL_SAI_RxCpltCallback()
635 (++) HAL_SAI_ErrorCallback()
642 * @brief Transmit an amount of data in blocking mode.
643 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
644 * the configuration information for SAI module.
645 * @param pData: Pointer to data buffer
646 * @param Size: Amount of data to be sent
647 * @param Timeout: Timeout duration
650 HAL_StatusTypeDef
HAL_SAI_Transmit(SAI_HandleTypeDef
*hsai
, uint8_t* pData
, uint16_t Size
, uint32_t Timeout
)
652 uint32_t tickstart
= HAL_GetTick();
654 if((pData
== NULL
) || (Size
== 0))
659 if(hsai
->State
== HAL_SAI_STATE_READY
)
664 hsai
->XferSize
= Size
;
665 hsai
->XferCount
= Size
;
666 hsai
->pBuffPtr
= pData
;
667 hsai
->State
= HAL_SAI_STATE_BUSY_TX
;
668 hsai
->ErrorCode
= HAL_SAI_ERROR_NONE
;
670 /* Check if the SAI is already enabled */
671 if((hsai
->Instance
->CR1
& SAI_xCR1_SAIEN
) == RESET
)
673 /* fill the fifo with data before to enabled the SAI */
675 /* Enable SAI peripheral */
676 __HAL_SAI_ENABLE(hsai
);
679 while(hsai
->XferCount
> 0)
681 /* Write data if the FIFO is not full */
682 if((hsai
->Instance
->SR
& SAI_xSR_FLVL
) != SAI_FIFOSTATUS_FULL
)
684 if((hsai
->Init
.DataSize
== SAI_DATASIZE_8
) && (hsai
->Init
.CompandingMode
== SAI_NOCOMPANDING
))
686 hsai
->Instance
->DR
= (*hsai
->pBuffPtr
++);
688 else if(hsai
->Init
.DataSize
<= SAI_DATASIZE_16
)
690 hsai
->Instance
->DR
= *((uint16_t *)hsai
->pBuffPtr
);
695 hsai
->Instance
->DR
= *((uint32_t *)hsai
->pBuffPtr
);
702 /* Check for the Timeout */
703 if((Timeout
!= HAL_MAX_DELAY
) && ((Timeout
== 0)||((HAL_GetTick() - tickstart
) > Timeout
)))
705 /* Update error code */
706 hsai
->ErrorCode
|= HAL_SAI_ERROR_TIMEOUT
;
708 /* Clear all the flags */
709 hsai
->Instance
->CLRFR
= 0xFFFFFFFFU
;
711 /* Disable SAI peripheral */
715 SET_BIT(hsai
->Instance
->CR2
, SAI_xCR2_FFLUSH
);
717 /* Change the SAI state */
718 hsai
->State
= HAL_SAI_STATE_READY
;
720 /* Process Unlocked */
728 hsai
->State
= HAL_SAI_STATE_READY
;
730 /* Process Unlocked */
742 * @brief Receive an amount of data in blocking mode.
743 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
744 * the configuration information for SAI module.
745 * @param pData: Pointer to data buffer
746 * @param Size: Amount of data to be received
747 * @param Timeout: Timeout duration
750 HAL_StatusTypeDef
HAL_SAI_Receive(SAI_HandleTypeDef
*hsai
, uint8_t *pData
, uint16_t Size
, uint32_t Timeout
)
752 uint32_t tickstart
= HAL_GetTick();
754 if((pData
== NULL
) || (Size
== 0))
759 if(hsai
->State
== HAL_SAI_STATE_READY
)
764 hsai
->pBuffPtr
= pData
;
765 hsai
->XferSize
= Size
;
766 hsai
->XferCount
= Size
;
767 hsai
->State
= HAL_SAI_STATE_BUSY_RX
;
768 hsai
->ErrorCode
= HAL_SAI_ERROR_NONE
;
770 /* Check if the SAI is already enabled */
771 if((hsai
->Instance
->CR1
& SAI_xCR1_SAIEN
) == RESET
)
773 /* Enable SAI peripheral */
774 __HAL_SAI_ENABLE(hsai
);
778 while(hsai
->XferCount
> 0)
780 if((hsai
->Instance
->SR
& SAI_xSR_FLVL
) != SAI_FIFOSTATUS_EMPTY
)
782 if((hsai
->Init
.DataSize
== SAI_DATASIZE_8
) && (hsai
->Init
.CompandingMode
== SAI_NOCOMPANDING
))
784 (*hsai
->pBuffPtr
++) = hsai
->Instance
->DR
;
786 else if(hsai
->Init
.DataSize
<= SAI_DATASIZE_16
)
788 *((uint16_t*)hsai
->pBuffPtr
) = hsai
->Instance
->DR
;
793 *((uint32_t*)hsai
->pBuffPtr
) = hsai
->Instance
->DR
;
800 /* Check for the Timeout */
801 if((Timeout
!= HAL_MAX_DELAY
) && ((Timeout
== 0)||((HAL_GetTick() - tickstart
) > Timeout
)))
803 /* Update error code */
804 hsai
->ErrorCode
|= HAL_SAI_ERROR_TIMEOUT
;
806 /* Clear all the flags */
807 hsai
->Instance
->CLRFR
= 0xFFFFFFFFU
;
809 /* Disable SAI peripheral */
813 SET_BIT(hsai
->Instance
->CR2
, SAI_xCR2_FFLUSH
);
815 /* Change the SAI state */
816 hsai
->State
= HAL_SAI_STATE_READY
;
818 /* Process Unlocked */
826 hsai
->State
= HAL_SAI_STATE_READY
;
828 /* Process Unlocked */
840 * @brief Transmit an amount of data in non-blocking mode with Interrupt.
841 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
842 * the configuration information for SAI module.
843 * @param pData: Pointer to data buffer
844 * @param Size: Amount of data to be sent
847 HAL_StatusTypeDef
HAL_SAI_Transmit_IT(SAI_HandleTypeDef
*hsai
, uint8_t *pData
, uint16_t Size
)
849 if((pData
== NULL
) || (Size
== 0))
854 if(hsai
->State
== HAL_SAI_STATE_READY
)
859 hsai
->pBuffPtr
= pData
;
860 hsai
->XferSize
= Size
;
861 hsai
->XferCount
= Size
;
862 hsai
->ErrorCode
= HAL_SAI_ERROR_NONE
;
863 hsai
->State
= HAL_SAI_STATE_BUSY_TX
;
865 if((hsai
->Init
.DataSize
== SAI_DATASIZE_8
) && (hsai
->Init
.CompandingMode
== SAI_NOCOMPANDING
))
867 hsai
->InterruptServiceRoutine
= SAI_Transmit_IT8Bit
;
869 else if(hsai
->Init
.DataSize
<= SAI_DATASIZE_16
)
871 hsai
->InterruptServiceRoutine
= SAI_Transmit_IT16Bit
;
875 hsai
->InterruptServiceRoutine
= SAI_Transmit_IT32Bit
;
878 /* Fill the fifo before starting the communication */
881 /* Enable FRQ and OVRUDR interrupts */
882 __HAL_SAI_ENABLE_IT(hsai
, SAI_InterruptFlag(hsai
, SAI_MODE_IT
));
884 /* Check if the SAI is already enabled */
885 if((hsai
->Instance
->CR1
& SAI_xCR1_SAIEN
) == RESET
)
887 /* Enable SAI peripheral */
888 __HAL_SAI_ENABLE(hsai
);
890 /* Process Unlocked */
902 * @brief Receive an amount of data in non-blocking mode with Interrupt.
903 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
904 * the configuration information for SAI module.
905 * @param pData: Pointer to data buffer
906 * @param Size: Amount of data to be received
909 HAL_StatusTypeDef
HAL_SAI_Receive_IT(SAI_HandleTypeDef
*hsai
, uint8_t *pData
, uint16_t Size
)
911 if((pData
== NULL
) || (Size
== 0))
916 if(hsai
->State
== HAL_SAI_STATE_READY
)
921 hsai
->pBuffPtr
= pData
;
922 hsai
->XferSize
= Size
;
923 hsai
->XferCount
= Size
;
924 hsai
->ErrorCode
= HAL_SAI_ERROR_NONE
;
925 hsai
->State
= HAL_SAI_STATE_BUSY_RX
;
927 if((hsai
->Init
.DataSize
== SAI_DATASIZE_8
) && (hsai
->Init
.CompandingMode
== SAI_NOCOMPANDING
))
929 hsai
->InterruptServiceRoutine
= SAI_Receive_IT8Bit
;
931 else if(hsai
->Init
.DataSize
<= SAI_DATASIZE_16
)
933 hsai
->InterruptServiceRoutine
= SAI_Receive_IT16Bit
;
937 hsai
->InterruptServiceRoutine
= SAI_Receive_IT32Bit
;
940 /* Enable TXE and OVRUDR interrupts */
941 __HAL_SAI_ENABLE_IT(hsai
, SAI_InterruptFlag(hsai
, SAI_MODE_IT
));
943 /* Check if the SAI is already enabled */
944 if((hsai
->Instance
->CR1
& SAI_xCR1_SAIEN
) == RESET
)
946 /* Enable SAI peripheral */
947 __HAL_SAI_ENABLE(hsai
);
950 /* Process Unlocked */
962 * @brief Pause the audio stream playing from the Media.
963 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
964 * the configuration information for SAI module.
967 HAL_StatusTypeDef
HAL_SAI_DMAPause(SAI_HandleTypeDef
*hsai
)
972 /* Pause the audio file playing by disabling the SAI DMA requests */
973 hsai
->Instance
->CR1
&= ~SAI_xCR1_DMAEN
;
975 /* Process Unlocked */
982 * @brief Resume the audio stream playing from the Media.
983 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
984 * the configuration information for SAI module.
987 HAL_StatusTypeDef
HAL_SAI_DMAResume(SAI_HandleTypeDef
*hsai
)
992 /* Enable the SAI DMA requests */
993 hsai
->Instance
->CR1
|= SAI_xCR1_DMAEN
;
995 /* If the SAI peripheral is still not enabled, enable it */
996 if ((hsai
->Instance
->CR1
& SAI_xCR1_SAIEN
) == RESET
)
998 /* Enable SAI peripheral */
999 __HAL_SAI_ENABLE(hsai
);
1002 /* Process Unlocked */
1009 * @brief Stop the audio stream playing from the Media.
1010 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
1011 * the configuration information for SAI module.
1012 * @retval HAL status
1014 HAL_StatusTypeDef
HAL_SAI_DMAStop(SAI_HandleTypeDef
*hsai
)
1016 /* Process Locked */
1019 /* Disable the SAI DMA request */
1020 hsai
->Instance
->CR1
&= ~SAI_xCR1_DMAEN
;
1022 /* Abort the SAI DMA Streams */
1023 if(hsai
->hdmatx
!= NULL
)
1025 if(HAL_DMA_Abort(hsai
->hdmatx
) != HAL_OK
)
1031 if(hsai
->hdmarx
!= NULL
)
1033 if(HAL_DMA_Abort(hsai
->hdmarx
) != HAL_OK
)
1039 /* Disable SAI peripheral */
1042 hsai
->State
= HAL_SAI_STATE_READY
;
1044 /* Process Unlocked */
1051 * @brief Abort the current transfer and disable the SAI.
1052 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
1053 * the configuration information for SAI module.
1054 * @retval HAL status
1056 HAL_StatusTypeDef
HAL_SAI_Abort(SAI_HandleTypeDef
*hsai
)
1058 /* Process Locked */
1061 /* Check SAI DMA is enabled or not */
1062 if((hsai
->Instance
->CR1
& SAI_xCR1_DMAEN
) == SAI_xCR1_DMAEN
)
1064 /* Disable the SAI DMA request */
1065 hsai
->Instance
->CR1
&= ~SAI_xCR1_DMAEN
;
1067 /* Abort the SAI DMA Streams */
1068 if(hsai
->hdmatx
!= NULL
)
1070 if(HAL_DMA_Abort(hsai
->hdmatx
) != HAL_OK
)
1076 if(hsai
->hdmarx
!= NULL
)
1078 if(HAL_DMA_Abort(hsai
->hdmarx
) != HAL_OK
)
1084 /* Disabled All interrupt and clear all the flag */
1085 hsai
->Instance
->IMR
= 0;
1086 hsai
->Instance
->CLRFR
= 0xFFFFFFFFU
;
1088 /* Disable SAI peripheral */
1091 /* Flush the fifo */
1092 SET_BIT(hsai
->Instance
->CR2
, SAI_xCR2_FFLUSH
);
1094 hsai
->State
= HAL_SAI_STATE_READY
;
1096 /* Process Unlocked */
1103 * @brief Transmit an amount of data in non-blocking mode with DMA.
1104 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
1105 * the configuration information for SAI module.
1106 * @param pData: Pointer to data buffer
1107 * @param Size: Amount of data to be sent
1108 * @retval HAL status
1110 HAL_StatusTypeDef
HAL_SAI_Transmit_DMA(SAI_HandleTypeDef
*hsai
, uint8_t *pData
, uint16_t Size
)
1112 if((pData
== NULL
) || (Size
== 0))
1117 if(hsai
->State
== HAL_SAI_STATE_READY
)
1119 /* Process Locked */
1122 hsai
->pBuffPtr
= pData
;
1123 hsai
->XferSize
= Size
;
1124 hsai
->XferCount
= Size
;
1125 hsai
->ErrorCode
= HAL_SAI_ERROR_NONE
;
1126 hsai
->State
= HAL_SAI_STATE_BUSY_TX
;
1128 /* Set the SAI Tx DMA Half transfer complete callback */
1129 hsai
->hdmatx
->XferHalfCpltCallback
= SAI_DMATxHalfCplt
;
1131 /* Set the SAI TxDMA transfer complete callback */
1132 hsai
->hdmatx
->XferCpltCallback
= SAI_DMATxCplt
;
1134 /* Set the DMA error callback */
1135 hsai
->hdmatx
->XferErrorCallback
= SAI_DMAError
;
1137 /* Set the DMA Tx abort callback */
1138 hsai
->hdmatx
->XferAbortCallback
= NULL
;
1140 /* Enable the Tx DMA Stream */
1141 if(HAL_DMA_Start_IT(hsai
->hdmatx
, (uint32_t)hsai
->pBuffPtr
, (uint32_t)&hsai
->Instance
->DR
, hsai
->XferSize
) != HAL_OK
)
1147 /* Check if the SAI is already enabled */
1148 if((hsai
->Instance
->CR1
& SAI_xCR1_SAIEN
) == RESET
)
1150 /* Enable SAI peripheral */
1151 __HAL_SAI_ENABLE(hsai
);
1154 /* Enable the interrupts for error handling */
1155 __HAL_SAI_ENABLE_IT(hsai
, SAI_InterruptFlag(hsai
, SAI_MODE_DMA
));
1157 /* Enable SAI Tx DMA Request */
1158 hsai
->Instance
->CR1
|= SAI_xCR1_DMAEN
;
1160 /* Process Unlocked */
1172 * @brief Receive an amount of data in non-blocking mode with DMA.
1173 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
1174 * the configuration information for SAI module.
1175 * @param pData: Pointer to data buffer
1176 * @param Size: Amount of data to be received
1177 * @retval HAL status
1179 HAL_StatusTypeDef
HAL_SAI_Receive_DMA(SAI_HandleTypeDef
*hsai
, uint8_t *pData
, uint16_t Size
)
1182 if((pData
== NULL
) || (Size
== 0))
1187 if(hsai
->State
== HAL_SAI_STATE_READY
)
1189 /* Process Locked */
1192 hsai
->pBuffPtr
= pData
;
1193 hsai
->XferSize
= Size
;
1194 hsai
->XferCount
= Size
;
1195 hsai
->ErrorCode
= HAL_SAI_ERROR_NONE
;
1196 hsai
->State
= HAL_SAI_STATE_BUSY_RX
;
1198 /* Set the SAI Rx DMA Half transfer complete callback */
1199 hsai
->hdmarx
->XferHalfCpltCallback
= SAI_DMARxHalfCplt
;
1201 /* Set the SAI Rx DMA transfer complete callback */
1202 hsai
->hdmarx
->XferCpltCallback
= SAI_DMARxCplt
;
1204 /* Set the DMA error callback */
1205 hsai
->hdmarx
->XferErrorCallback
= SAI_DMAError
;
1207 /* Set the DMA Rx abort callback */
1208 hsai
->hdmarx
->XferAbortCallback
= NULL
;
1210 /* Enable the Rx DMA Stream */
1211 if(HAL_DMA_Start_IT(hsai
->hdmarx
, (uint32_t)&hsai
->Instance
->DR
, (uint32_t)hsai
->pBuffPtr
, hsai
->XferSize
) != HAL_OK
)
1217 /* Check if the SAI is already enabled */
1218 if((hsai
->Instance
->CR1
& SAI_xCR1_SAIEN
) == RESET
)
1220 /* Enable SAI peripheral */
1221 __HAL_SAI_ENABLE(hsai
);
1224 /* Enable the interrupts for error handling */
1225 __HAL_SAI_ENABLE_IT(hsai
, SAI_InterruptFlag(hsai
, SAI_MODE_DMA
));
1227 /* Enable SAI Rx DMA Request */
1228 hsai
->Instance
->CR1
|= SAI_xCR1_DMAEN
;
1230 /* Process Unlocked */
1242 * @brief Enable the Tx mute mode.
1243 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
1244 * the configuration information for SAI module.
1245 * @param val: value sent during the mute @ref SAI_Block_Mute_Value
1246 * @retval HAL status
1248 HAL_StatusTypeDef
HAL_SAI_EnableTxMuteMode(SAI_HandleTypeDef
*hsai
, uint16_t val
)
1250 assert_param(IS_SAI_BLOCK_MUTE_VALUE(val
));
1252 if(hsai
->State
!= HAL_SAI_STATE_RESET
)
1254 CLEAR_BIT(hsai
->Instance
->CR2
, SAI_xCR2_MUTEVAL
| SAI_xCR2_MUTE
);
1255 SET_BIT(hsai
->Instance
->CR2
, SAI_xCR2_MUTE
| val
);
1262 * @brief Disable the Tx mute mode.
1263 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
1264 * the configuration information for SAI module.
1265 * @retval HAL status
1267 HAL_StatusTypeDef
HAL_SAI_DisableTxMuteMode(SAI_HandleTypeDef
*hsai
)
1269 if(hsai
->State
!= HAL_SAI_STATE_RESET
)
1271 CLEAR_BIT(hsai
->Instance
->CR2
, SAI_xCR2_MUTEVAL
| SAI_xCR2_MUTE
);
1278 * @brief Enable the Rx mute detection.
1279 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
1280 * the configuration information for SAI module.
1281 * @param callback: function called when the mute is detected.
1282 * @param counter: number a data before mute detection max 63.
1283 * @retval HAL status
1285 HAL_StatusTypeDef
HAL_SAI_EnableRxMuteMode(SAI_HandleTypeDef
*hsai
, SAIcallback callback
, uint16_t counter
)
1287 assert_param(IS_SAI_BLOCK_MUTE_COUNTER(counter
));
1289 if(hsai
->State
!= HAL_SAI_STATE_RESET
)
1291 /* set the mute counter */
1292 CLEAR_BIT(hsai
->Instance
->CR2
, SAI_xCR2_MUTECNT
);
1293 SET_BIT(hsai
->Instance
->CR2
, (uint32_t)((uint32_t)counter
<< SAI_xCR2_MUTECNT_OFFSET
));
1294 hsai
->mutecallback
= callback
;
1295 /* enable the IT interrupt */
1296 __HAL_SAI_ENABLE_IT(hsai
, SAI_IT_MUTEDET
);
1303 * @brief Disable the Rx mute detection.
1304 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
1305 * the configuration information for SAI module.
1306 * @retval HAL status
1308 HAL_StatusTypeDef
HAL_SAI_DisableRxMuteMode(SAI_HandleTypeDef
*hsai
)
1310 if(hsai
->State
!= HAL_SAI_STATE_RESET
)
1312 /* set the mutecallback to NULL */
1313 hsai
->mutecallback
= (SAIcallback
)NULL
;
1314 /* enable the IT interrupt */
1315 __HAL_SAI_DISABLE_IT(hsai
, SAI_IT_MUTEDET
);
1322 * @brief Handle SAI interrupt request.
1323 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
1324 * the configuration information for SAI module.
1327 void HAL_SAI_IRQHandler(SAI_HandleTypeDef
*hsai
)
1329 if(hsai
->State
!= HAL_SAI_STATE_RESET
)
1331 uint32_t itflags
= hsai
->Instance
->SR
;
1332 uint32_t itsources
= hsai
->Instance
->IMR
;
1333 uint32_t cr1config
= hsai
->Instance
->CR1
;
1336 /* SAI Fifo request interrupt occured ------------------------------------*/
1337 if(((itflags
& SAI_xSR_FREQ
) == SAI_xSR_FREQ
) && ((itsources
& SAI_IT_FREQ
) == SAI_IT_FREQ
))
1339 hsai
->InterruptServiceRoutine(hsai
);
1341 /* SAI Overrun error interrupt occurred ----------------------------------*/
1342 else if(((itflags
& SAI_FLAG_OVRUDR
) == SAI_FLAG_OVRUDR
) && ((itsources
& SAI_IT_OVRUDR
) == SAI_IT_OVRUDR
))
1344 /* Clear the SAI Overrun flag */
1345 __HAL_SAI_CLEAR_FLAG(hsai
, SAI_FLAG_OVRUDR
);
1346 /* Get the SAI error code */
1347 tmperror
= ((hsai
->State
== HAL_SAI_STATE_BUSY_RX
) ? HAL_SAI_ERROR_OVR
: HAL_SAI_ERROR_UDR
);
1348 /* Change the SAI error code */
1349 hsai
->ErrorCode
|= tmperror
;
1350 /* the transfer is not stopped, we will forward the information to the user and we let the user decide what needs to be done */
1351 HAL_SAI_ErrorCallback(hsai
);
1353 /* SAI mutedet interrupt occurred ----------------------------------*/
1354 else if(((itflags
& SAI_FLAG_MUTEDET
) == SAI_FLAG_MUTEDET
) && ((itsources
& SAI_IT_MUTEDET
) == SAI_IT_MUTEDET
))
1356 /* Clear the SAI mutedet flag */
1357 __HAL_SAI_CLEAR_FLAG(hsai
, SAI_FLAG_MUTEDET
);
1358 /* call the call back function */
1359 if(hsai
->mutecallback
!= (SAIcallback
)NULL
)
1361 /* inform the user that an RX mute event has been detected */
1362 hsai
->mutecallback();
1365 /* SAI AFSDET interrupt occurred ----------------------------------*/
1366 else if(((itflags
& SAI_FLAG_AFSDET
) == SAI_FLAG_AFSDET
) && ((itsources
& SAI_IT_AFSDET
) == SAI_IT_AFSDET
))
1368 /* Change the SAI error code */
1369 hsai
->ErrorCode
|= HAL_SAI_ERROR_AFSDET
;
1370 /* Check SAI DMA is enabled or not */
1371 if((cr1config
& SAI_xCR1_DMAEN
) == SAI_xCR1_DMAEN
)
1373 /* Abort the SAI DMA Streams */
1374 if(hsai
->hdmatx
!= NULL
)
1376 /* Set the DMA Tx abort callback */
1377 hsai
->hdmatx
->XferAbortCallback
= SAI_DMAAbort
;
1379 /* Abort DMA in IT mode */
1380 HAL_DMA_Abort_IT(hsai
->hdmatx
);
1382 else if(hsai
->hdmarx
!= NULL
)
1384 /* Set the DMA Rx abort callback */
1385 hsai
->hdmarx
->XferAbortCallback
= SAI_DMAAbort
;
1386 /* Abort DMA in IT mode */
1387 HAL_DMA_Abort_IT(hsai
->hdmarx
);
1393 HAL_SAI_Abort(hsai
);
1395 /* Set error callback */
1396 HAL_SAI_ErrorCallback(hsai
);
1399 /* SAI LFSDET interrupt occurred ----------------------------------*/
1400 else if(((itflags
& SAI_FLAG_LFSDET
) == SAI_FLAG_LFSDET
) && ((itsources
& SAI_IT_LFSDET
) == SAI_IT_LFSDET
))
1402 /* Change the SAI error code */
1403 hsai
->ErrorCode
|= HAL_SAI_ERROR_LFSDET
;
1405 /* Check SAI DMA is enabled or not */
1406 if((cr1config
& SAI_xCR1_DMAEN
) == SAI_xCR1_DMAEN
)
1408 /* Abort the SAI DMA Streams */
1409 if(hsai
->hdmatx
!= NULL
)
1411 /* Set the DMA Tx abort callback */
1412 hsai
->hdmatx
->XferAbortCallback
= SAI_DMAAbort
;
1413 /* Abort DMA in IT mode */
1414 HAL_DMA_Abort_IT(hsai
->hdmatx
);
1416 else if(hsai
->hdmarx
!= NULL
)
1418 /* Set the DMA Rx abort callback */
1419 hsai
->hdmarx
->XferAbortCallback
= SAI_DMAAbort
;
1420 /* Abort DMA in IT mode */
1421 HAL_DMA_Abort_IT(hsai
->hdmarx
);
1427 HAL_SAI_Abort(hsai
);
1429 /* Set error callback */
1430 HAL_SAI_ErrorCallback(hsai
);
1433 /* SAI WCKCFG interrupt occurred ----------------------------------*/
1434 else if(((itflags
& SAI_FLAG_WCKCFG
) == SAI_FLAG_WCKCFG
) && ((itsources
& SAI_IT_WCKCFG
) == SAI_IT_WCKCFG
))
1436 /* Change the SAI error code */
1437 hsai
->ErrorCode
|= HAL_SAI_ERROR_WCKCFG
;
1439 /* Abort the SAI DMA Streams */
1440 if(hsai
->hdmatx
!= NULL
)
1442 /* Set the DMA Tx abort callback */
1443 hsai
->hdmatx
->XferAbortCallback
= SAI_DMAAbort
;
1444 /* Abort DMA in IT mode */
1445 HAL_DMA_Abort_IT(hsai
->hdmatx
);
1447 else if(hsai
->hdmarx
!= NULL
)
1449 /* Set the DMA Rx abort callback */
1450 hsai
->hdmarx
->XferAbortCallback
= SAI_DMAAbort
;
1451 /* Abort DMA in IT mode */
1452 HAL_DMA_Abort_IT(hsai
->hdmarx
);
1456 /* If WCKCFG occurs, SAI audio block is automatically disabled */
1457 /* Disable all interrupts and clear all flags */
1458 hsai
->Instance
->IMR
= 0U;
1459 hsai
->Instance
->CLRFR
= 0xFFFFFFFFU
;
1460 /* Set the SAI state to ready to be able to start again the process */
1461 hsai
->State
= HAL_SAI_STATE_READY
;
1463 /* Initialize XferCount */
1464 hsai
->XferCount
= 0U;
1466 /* SAI error Callback */
1467 HAL_SAI_ErrorCallback(hsai
);
1470 /* SAI CNRDY interrupt occurred ----------------------------------*/
1471 else if(((itflags
& SAI_FLAG_CNRDY
) == SAI_FLAG_CNRDY
) && ((itsources
& SAI_IT_CNRDY
) == SAI_IT_CNRDY
))
1473 /* Clear the SAI CNRDY flag */
1474 __HAL_SAI_CLEAR_FLAG(hsai
, SAI_FLAG_CNRDY
);
1475 /* Change the SAI error code */
1476 hsai
->ErrorCode
|= HAL_SAI_ERROR_CNREADY
;
1477 /* the transfer is not stopped, we will forward the information to the user and we let the user decide what needs to be done */
1478 HAL_SAI_ErrorCallback(hsai
);
1488 * @brief Tx Transfer completed callback.
1489 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
1490 * the configuration information for SAI module.
1493 __weak
void HAL_SAI_TxCpltCallback(SAI_HandleTypeDef
*hsai
)
1495 /* Prevent unused argument(s) compilation warning */
1498 /* NOTE : This function should not be modified, when the callback is needed,
1499 the HAL_SAI_TxCpltCallback could be implemented in the user file
1504 * @brief Tx Transfer Half completed callback.
1505 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
1506 * the configuration information for SAI module.
1509 __weak
void HAL_SAI_TxHalfCpltCallback(SAI_HandleTypeDef
*hsai
)
1511 /* Prevent unused argument(s) compilation warning */
1514 /* NOTE : This function should not be modified, when the callback is needed,
1515 the HAL_SAI_TxHalfCpltCallback could be implemented in the user file
1520 * @brief Rx Transfer completed callback.
1521 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
1522 * the configuration information for SAI module.
1525 __weak
void HAL_SAI_RxCpltCallback(SAI_HandleTypeDef
*hsai
)
1527 /* Prevent unused argument(s) compilation warning */
1530 /* NOTE : This function should not be modified, when the callback is needed,
1531 the HAL_SAI_RxCpltCallback could be implemented in the user file
1536 * @brief Rx Transfer half completed callback.
1537 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
1538 * the configuration information for SAI module.
1541 __weak
void HAL_SAI_RxHalfCpltCallback(SAI_HandleTypeDef
*hsai
)
1543 /* Prevent unused argument(s) compilation warning */
1546 /* NOTE : This function should not be modified, when the callback is needed,
1547 the HAL_SAI_RxHalfCpltCallback could be implemented in the user file
1552 * @brief SAI error callback.
1553 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
1554 * the configuration information for SAI module.
1557 __weak
void HAL_SAI_ErrorCallback(SAI_HandleTypeDef
*hsai
)
1559 /* Prevent unused argument(s) compilation warning */
1562 /* NOTE : This function should not be modified, when the callback is needed,
1563 the HAL_SAI_ErrorCallback could be implemented in the user file
1572 /** @defgroup SAI_Exported_Functions_Group3 Peripheral State functions
1573 * @brief Peripheral State functions
1576 ===============================================================================
1577 ##### Peripheral State and Errors functions #####
1578 ===============================================================================
1580 This subsection permits to get in run-time the status of the peripheral
1588 * @brief Return the SAI handle state.
1589 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
1590 * the configuration information for SAI module.
1593 HAL_SAI_StateTypeDef
HAL_SAI_GetState(SAI_HandleTypeDef
*hsai
)
1599 * @brief Return the SAI error code.
1600 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
1601 * the configuration information for the specified SAI Block.
1602 * @retval SAI Error Code
1604 uint32_t HAL_SAI_GetError(SAI_HandleTypeDef
*hsai
)
1606 return hsai
->ErrorCode
;
1616 /** @addtogroup SAI_Private_Functions
1617 * @brief Private functions
1622 * @brief Initialize the SAI I2S protocol according to the specified parameters
1623 * in the SAI_InitTypeDef and create the associated handle.
1624 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
1625 * the configuration information for SAI module.
1626 * @param protocol: one of the supported protocol.
1627 * @param datasize: one of the supported datasize @ref SAI_Protocol_DataSize
1628 * the configuration information for SAI module.
1629 * @param nbslot: number of slot minimum value is 2 and max is 16.
1630 * the value must be a multiple of 2.
1631 * @retval HAL status
1633 static HAL_StatusTypeDef
SAI_InitI2S(SAI_HandleTypeDef
*hsai
, uint32_t protocol
, uint32_t datasize
, uint32_t nbslot
)
1635 hsai
->Init
.Protocol
= SAI_FREE_PROTOCOL
;
1636 hsai
->Init
.FirstBit
= SAI_FIRSTBIT_MSB
;
1637 /* Compute ClockStrobing according AudioMode */
1638 if((hsai
->Init
.AudioMode
== SAI_MODEMASTER_TX
) || (hsai
->Init
.AudioMode
== SAI_MODESLAVE_TX
))
1640 hsai
->Init
.ClockStrobing
= SAI_CLOCKSTROBING_FALLINGEDGE
;
1644 hsai
->Init
.ClockStrobing
= SAI_CLOCKSTROBING_RISINGEDGE
;
1646 hsai
->FrameInit
.FSDefinition
= SAI_FS_CHANNEL_IDENTIFICATION
;
1647 hsai
->SlotInit
.SlotActive
= SAI_SLOTACTIVE_ALL
;
1648 hsai
->SlotInit
.FirstBitOffset
= 0;
1649 hsai
->SlotInit
.SlotNumber
= nbslot
;
1651 /* in IS2 the number of slot must be even */
1652 if((nbslot
& 0x1) != 0 )
1659 case SAI_I2S_STANDARD
:
1660 hsai
->FrameInit
.FSPolarity
= SAI_FS_ACTIVE_LOW
;
1661 hsai
->FrameInit
.FSOffset
= SAI_FS_BEFOREFIRSTBIT
;
1663 case SAI_I2S_MSBJUSTIFIED
:
1664 case SAI_I2S_LSBJUSTIFIED
:
1665 hsai
->FrameInit
.FSPolarity
= SAI_FS_ACTIVE_HIGH
;
1666 hsai
->FrameInit
.FSOffset
= SAI_FS_FIRSTBIT
;
1672 /* Frame definition */
1675 case SAI_PROTOCOL_DATASIZE_16BIT
:
1676 hsai
->Init
.DataSize
= SAI_DATASIZE_16
;
1677 hsai
->FrameInit
.FrameLength
= 32*(nbslot
/2);
1678 hsai
->FrameInit
.ActiveFrameLength
= 16*(nbslot
/2);
1679 hsai
->SlotInit
.SlotSize
= SAI_SLOTSIZE_16B
;
1681 case SAI_PROTOCOL_DATASIZE_16BITEXTENDED
:
1682 hsai
->Init
.DataSize
= SAI_DATASIZE_16
;
1683 hsai
->FrameInit
.FrameLength
= 64*(nbslot
/2);
1684 hsai
->FrameInit
.ActiveFrameLength
= 32*(nbslot
/2);
1685 hsai
->SlotInit
.SlotSize
= SAI_SLOTSIZE_32B
;
1687 case SAI_PROTOCOL_DATASIZE_24BIT
:
1688 hsai
->Init
.DataSize
= SAI_DATASIZE_24
;
1689 hsai
->FrameInit
.FrameLength
= 64*(nbslot
/2);
1690 hsai
->FrameInit
.ActiveFrameLength
= 32*(nbslot
/2);
1691 hsai
->SlotInit
.SlotSize
= SAI_SLOTSIZE_32B
;
1693 case SAI_PROTOCOL_DATASIZE_32BIT
:
1694 hsai
->Init
.DataSize
= SAI_DATASIZE_32
;
1695 hsai
->FrameInit
.FrameLength
= 64*(nbslot
/2);
1696 hsai
->FrameInit
.ActiveFrameLength
= 32*(nbslot
/2);
1697 hsai
->SlotInit
.SlotSize
= SAI_SLOTSIZE_32B
;
1702 if(protocol
== SAI_I2S_LSBJUSTIFIED
)
1704 if (datasize
== SAI_PROTOCOL_DATASIZE_16BITEXTENDED
)
1706 hsai
->SlotInit
.FirstBitOffset
= 16;
1708 if (datasize
== SAI_PROTOCOL_DATASIZE_24BIT
)
1710 hsai
->SlotInit
.FirstBitOffset
= 8;
1717 * @brief Initialize the SAI PCM protocol according to the specified parameters
1718 * in the SAI_InitTypeDef and create the associated handle.
1719 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
1720 * the configuration information for SAI module.
1721 * @param protocol: one of the supported protocol
1722 * @param datasize: one of the supported datasize @ref SAI_Protocol_DataSize
1723 * @param nbslot: number of slot minimum value is 1 and the max is 16.
1724 * @retval HAL status
1726 static HAL_StatusTypeDef
SAI_InitPCM(SAI_HandleTypeDef
*hsai
, uint32_t protocol
, uint32_t datasize
, uint32_t nbslot
)
1728 hsai
->Init
.Protocol
= SAI_FREE_PROTOCOL
;
1729 hsai
->Init
.FirstBit
= SAI_FIRSTBIT_MSB
;
1730 /* Compute ClockStrobing according AudioMode */
1731 if((hsai
->Init
.AudioMode
== SAI_MODEMASTER_TX
) || (hsai
->Init
.AudioMode
== SAI_MODESLAVE_TX
))
1733 hsai
->Init
.ClockStrobing
= SAI_CLOCKSTROBING_RISINGEDGE
;
1737 hsai
->Init
.ClockStrobing
= SAI_CLOCKSTROBING_FALLINGEDGE
;
1739 hsai
->FrameInit
.FSDefinition
= SAI_FS_STARTFRAME
;
1740 hsai
->FrameInit
.FSPolarity
= SAI_FS_ACTIVE_HIGH
;
1741 hsai
->FrameInit
.FSOffset
= SAI_FS_BEFOREFIRSTBIT
;
1742 hsai
->SlotInit
.FirstBitOffset
= 0;
1743 hsai
->SlotInit
.SlotNumber
= nbslot
;
1744 hsai
->SlotInit
.SlotActive
= SAI_SLOTACTIVE_ALL
;
1748 case SAI_PCM_SHORT
:
1749 hsai
->FrameInit
.ActiveFrameLength
= 1;
1752 hsai
->FrameInit
.ActiveFrameLength
= 13;
1760 case SAI_PROTOCOL_DATASIZE_16BIT
:
1761 hsai
->Init
.DataSize
= SAI_DATASIZE_16
;
1762 hsai
->FrameInit
.FrameLength
= 16 * nbslot
;
1763 hsai
->SlotInit
.SlotSize
= SAI_SLOTSIZE_16B
;
1765 case SAI_PROTOCOL_DATASIZE_16BITEXTENDED
:
1766 hsai
->Init
.DataSize
= SAI_DATASIZE_16
;
1767 hsai
->FrameInit
.FrameLength
= 32 * nbslot
;
1768 hsai
->SlotInit
.SlotSize
= SAI_SLOTSIZE_32B
;
1770 case SAI_PROTOCOL_DATASIZE_24BIT
:
1771 hsai
->Init
.DataSize
= SAI_DATASIZE_24
;
1772 hsai
->FrameInit
.FrameLength
= 32 * nbslot
;
1773 hsai
->SlotInit
.SlotSize
= SAI_SLOTSIZE_32B
;
1775 case SAI_PROTOCOL_DATASIZE_32BIT
:
1776 hsai
->Init
.DataSize
= SAI_DATASIZE_32
;
1777 hsai
->FrameInit
.FrameLength
= 32 * nbslot
;
1778 hsai
->SlotInit
.SlotSize
= SAI_SLOTSIZE_32B
;
1788 * @brief Fill the fifo.
1789 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
1790 * the configuration information for SAI module.
1793 static void SAI_FillFifo(SAI_HandleTypeDef
*hsai
)
1795 /* fill the fifo with data before to enabled the SAI */
1796 while(((hsai
->Instance
->SR
& SAI_xSR_FLVL
) != SAI_FIFOSTATUS_FULL
) && (hsai
->XferCount
> 0))
1798 if((hsai
->Init
.DataSize
== SAI_DATASIZE_8
) && (hsai
->Init
.CompandingMode
== SAI_NOCOMPANDING
))
1800 hsai
->Instance
->DR
= (*hsai
->pBuffPtr
++);
1802 else if(hsai
->Init
.DataSize
<= SAI_DATASIZE_16
)
1804 hsai
->Instance
->DR
= *((uint32_t *)hsai
->pBuffPtr
);
1809 hsai
->Instance
->DR
= *((uint32_t *)hsai
->pBuffPtr
);
1817 * @brief Return the interrupt flag to set according the SAI setup.
1818 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
1819 * the configuration information for SAI module.
1820 * @param mode: SAI_MODE_DMA or SAI_MODE_IT
1821 * @retval the list of the IT flag to enable
1823 static uint32_t SAI_InterruptFlag(SAI_HandleTypeDef
*hsai
, uint32_t mode
)
1825 uint32_t tmpIT
= SAI_IT_OVRUDR
;
1827 if(mode
== SAI_MODE_IT
)
1829 tmpIT
|= SAI_IT_FREQ
;
1832 if((hsai
->Init
.Protocol
== SAI_AC97_PROTOCOL
) &&
1833 ((hsai
->Init
.AudioMode
== SAI_MODESLAVE_RX
) || (hsai
->Init
.AudioMode
== SAI_MODEMASTER_RX
)))
1835 tmpIT
|= SAI_IT_CNRDY
;
1838 if((hsai
->Init
.AudioMode
== SAI_MODESLAVE_RX
) || (hsai
->Init
.AudioMode
== SAI_MODESLAVE_TX
))
1840 tmpIT
|= SAI_IT_AFSDET
| SAI_IT_LFSDET
;
1844 /* hsai has been configured in master mode */
1845 tmpIT
|= SAI_IT_WCKCFG
;
1851 * @brief Disable the SAI and wait for the disabling.
1852 * @param hsai : pointer to a SAI_HandleTypeDef structure that contains
1853 * the configuration information for SAI module.
1856 static HAL_StatusTypeDef
SAI_Disable(SAI_HandleTypeDef
*hsai
)
1858 register uint32_t count
= SAI_DEFAULT_TIMEOUT
* (SystemCoreClock
/7/1000);
1859 HAL_StatusTypeDef status
= HAL_OK
;
1861 /* Disable the SAI instance */
1862 __HAL_SAI_DISABLE(hsai
);
1866 /* Check for the Timeout */
1869 /* Update error code */
1870 hsai
->ErrorCode
|= HAL_SAI_ERROR_TIMEOUT
;
1871 status
= HAL_TIMEOUT
;
1874 } while((hsai
->Instance
->CR1
& SAI_xCR1_SAIEN
) != RESET
);
1880 * @brief Tx Handler for Transmit in Interrupt mode 8-Bit transfer.
1881 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
1882 * the configuration information for SAI module.
1885 static void SAI_Transmit_IT8Bit(SAI_HandleTypeDef
*hsai
)
1887 if(hsai
->XferCount
== 0)
1889 /* Handle the end of the transmission */
1890 /* Disable FREQ and OVRUDR interrupts */
1891 __HAL_SAI_DISABLE_IT(hsai
, SAI_InterruptFlag(hsai
, SAI_MODE_IT
));
1892 hsai
->State
= HAL_SAI_STATE_READY
;
1893 HAL_SAI_TxCpltCallback(hsai
);
1897 /* Write data on DR register */
1898 hsai
->Instance
->DR
= (*hsai
->pBuffPtr
++);
1904 * @brief Tx Handler for Transmit in Interrupt mode for 16-Bit transfer.
1905 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
1906 * the configuration information for SAI module.
1909 static void SAI_Transmit_IT16Bit(SAI_HandleTypeDef
*hsai
)
1911 if(hsai
->XferCount
== 0)
1913 /* Handle the end of the transmission */
1914 /* Disable FREQ and OVRUDR interrupts */
1915 __HAL_SAI_DISABLE_IT(hsai
, SAI_InterruptFlag(hsai
, SAI_MODE_IT
));
1916 hsai
->State
= HAL_SAI_STATE_READY
;
1917 HAL_SAI_TxCpltCallback(hsai
);
1921 /* Write data on DR register */
1922 hsai
->Instance
->DR
= *(uint16_t *)hsai
->pBuffPtr
;
1929 * @brief Tx Handler for Transmit in Interrupt mode for 32-Bit transfer.
1930 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
1931 * the configuration information for SAI module.
1934 static void SAI_Transmit_IT32Bit(SAI_HandleTypeDef
*hsai
)
1936 if(hsai
->XferCount
== 0)
1938 /* Handle the end of the transmission */
1939 /* Disable FREQ and OVRUDR interrupts */
1940 __HAL_SAI_DISABLE_IT(hsai
, SAI_InterruptFlag(hsai
, SAI_MODE_IT
));
1941 hsai
->State
= HAL_SAI_STATE_READY
;
1942 HAL_SAI_TxCpltCallback(hsai
);
1946 /* Write data on DR register */
1947 hsai
->Instance
->DR
= *(uint32_t *)hsai
->pBuffPtr
;
1954 * @brief Rx Handler for Receive in Interrupt mode 8-Bit transfer.
1955 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
1956 * the configuration information for SAI module.
1959 static void SAI_Receive_IT8Bit(SAI_HandleTypeDef
*hsai
)
1962 (*hsai
->pBuffPtr
++) = hsai
->Instance
->DR
;
1965 /* Check end of the transfer */
1966 if(hsai
->XferCount
== 0)
1968 /* Disable TXE and OVRUDR interrupts */
1969 __HAL_SAI_DISABLE_IT(hsai
, SAI_InterruptFlag(hsai
, SAI_MODE_IT
));
1971 /* Clear the SAI Overrun flag */
1972 __HAL_SAI_CLEAR_FLAG(hsai
, SAI_FLAG_OVRUDR
);
1974 hsai
->State
= HAL_SAI_STATE_READY
;
1975 HAL_SAI_RxCpltCallback(hsai
);
1980 * @brief Rx Handler for Receive in Interrupt mode for 16-Bit transfer.
1981 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
1982 * the configuration information for SAI module.
1985 static void SAI_Receive_IT16Bit(SAI_HandleTypeDef
*hsai
)
1988 *(uint16_t*)hsai
->pBuffPtr
= hsai
->Instance
->DR
;
1992 /* Check end of the transfer */
1993 if(hsai
->XferCount
== 0)
1995 /* Disable TXE and OVRUDR interrupts */
1996 __HAL_SAI_DISABLE_IT(hsai
, SAI_InterruptFlag(hsai
, SAI_MODE_IT
));
1998 /* Clear the SAI Overrun flag */
1999 __HAL_SAI_CLEAR_FLAG(hsai
, SAI_FLAG_OVRUDR
);
2001 hsai
->State
= HAL_SAI_STATE_READY
;
2002 HAL_SAI_RxCpltCallback(hsai
);
2006 * @brief Rx Handler for Receive in Interrupt mode for 32-Bit transfer.
2007 * @param hsai: pointer to a SAI_HandleTypeDef structure that contains
2008 * the configuration information for SAI module.
2011 static void SAI_Receive_IT32Bit(SAI_HandleTypeDef
*hsai
)
2014 *(uint32_t*)hsai
->pBuffPtr
= hsai
->Instance
->DR
;
2018 /* Check end of the transfer */
2019 if(hsai
->XferCount
== 0)
2021 /* Disable TXE and OVRUDR interrupts */
2022 __HAL_SAI_DISABLE_IT(hsai
, SAI_InterruptFlag(hsai
, SAI_MODE_IT
));
2024 /* Clear the SAI Overrun flag */
2025 __HAL_SAI_CLEAR_FLAG(hsai
, SAI_FLAG_OVRUDR
);
2027 hsai
->State
= HAL_SAI_STATE_READY
;
2028 HAL_SAI_RxCpltCallback(hsai
);
2033 * @brief DMA SAI transmit process complete callback.
2034 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
2035 * the configuration information for the specified DMA module.
2038 static void SAI_DMATxCplt(DMA_HandleTypeDef
*hdma
)
2040 SAI_HandleTypeDef
* hsai
= (SAI_HandleTypeDef
*)((DMA_HandleTypeDef
* )hdma
)->Parent
;
2042 if((hdma
->Instance
->CR
& DMA_SxCR_CIRC
) == 0)
2044 hsai
->XferCount
= 0;
2046 /* Disable SAI Tx DMA Request */
2047 hsai
->Instance
->CR1
&= (uint32_t)(~SAI_xCR1_DMAEN
);
2049 /* Stop the interrupts error handling */
2050 __HAL_SAI_DISABLE_IT(hsai
, SAI_InterruptFlag(hsai
, SAI_MODE_DMA
));
2052 hsai
->State
= HAL_SAI_STATE_READY
;
2054 HAL_SAI_TxCpltCallback(hsai
);
2058 * @brief DMA SAI transmit process half complete callback.
2059 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
2060 * the configuration information for the specified DMA module.
2063 static void SAI_DMATxHalfCplt(DMA_HandleTypeDef
*hdma
)
2065 SAI_HandleTypeDef
* hsai
= (SAI_HandleTypeDef
*)((DMA_HandleTypeDef
*)hdma
)->Parent
;
2067 HAL_SAI_TxHalfCpltCallback(hsai
);
2071 * @brief DMA SAI receive process complete callback.
2072 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
2073 * the configuration information for the specified DMA module.
2076 static void SAI_DMARxCplt(DMA_HandleTypeDef
*hdma
)
2078 SAI_HandleTypeDef
* hsai
= ( SAI_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
2079 if((hdma
->Instance
->CR
& DMA_SxCR_CIRC
) == 0)
2081 /* Disable Rx DMA Request */
2082 hsai
->Instance
->CR1
&= (uint32_t)(~SAI_xCR1_DMAEN
);
2083 hsai
->XferCount
= 0;
2085 /* Stop the interrupts error handling */
2086 __HAL_SAI_DISABLE_IT(hsai
, SAI_InterruptFlag(hsai
, SAI_MODE_DMA
));
2088 hsai
->State
= HAL_SAI_STATE_READY
;
2090 HAL_SAI_RxCpltCallback(hsai
);
2094 * @brief DMA SAI receive process half complete callback
2095 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
2096 * the configuration information for the specified DMA module.
2099 static void SAI_DMARxHalfCplt(DMA_HandleTypeDef
*hdma
)
2101 SAI_HandleTypeDef
* hsai
= (SAI_HandleTypeDef
*)((DMA_HandleTypeDef
*)hdma
)->Parent
;
2103 HAL_SAI_RxHalfCpltCallback(hsai
);
2106 * @brief DMA SAI communication error callback.
2107 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
2108 * the configuration information for the specified DMA module.
2111 static void SAI_DMAError(DMA_HandleTypeDef
*hdma
)
2113 SAI_HandleTypeDef
* hsai
= ( SAI_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
2115 /* Set SAI error code */
2116 hsai
->ErrorCode
|= HAL_SAI_ERROR_DMA
;
2118 if((hsai
->hdmatx
->ErrorCode
== HAL_DMA_ERROR_TE
) || (hsai
->hdmarx
->ErrorCode
== HAL_DMA_ERROR_TE
))
2120 /* Disable the SAI DMA request */
2121 hsai
->Instance
->CR1
&= ~SAI_xCR1_DMAEN
;
2123 /* Disable SAI peripheral */
2126 /* Set the SAI state ready to be able to start again the process */
2127 hsai
->State
= HAL_SAI_STATE_READY
;
2129 /* Initialize XferCount */
2130 hsai
->XferCount
= 0U;
2132 /* SAI error Callback */
2133 HAL_SAI_ErrorCallback(hsai
);
2137 * @brief DMA SAI Abort callback.
2138 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
2139 * the configuration information for the specified DMA module.
2142 static void SAI_DMAAbort(DMA_HandleTypeDef
*hdma
)
2144 SAI_HandleTypeDef
* hsai
= ( SAI_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
2146 /* Disable DMA request */
2147 hsai
->Instance
->CR1
&= ~SAI_xCR1_DMAEN
;
2149 /* Disable all interrupts and clear all flags */
2150 hsai
->Instance
->IMR
= 0U;
2151 hsai
->Instance
->CLRFR
= 0xFFFFFFFFU
;
2153 if(hsai
->ErrorCode
!= HAL_SAI_ERROR_WCKCFG
)
2155 /* Disable SAI peripheral */
2158 /* Flush the fifo */
2159 SET_BIT(hsai
->Instance
->CR2
, SAI_xCR2_FFLUSH
);
2161 /* Set the SAI state to ready to be able to start again the process */
2162 hsai
->State
= HAL_SAI_STATE_READY
;
2164 /* Initialize XferCount */
2165 hsai
->XferCount
= 0U;
2167 /* SAI error Callback */
2168 HAL_SAI_ErrorCallback(hsai
);
2175 #endif /* HAL_SAI_MODULE_ENABLED */
2184 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/