Merge pull request #11189 from klutvott123/move-telemetry-displayport-init
[betaflight.git] / lib / main / STM32F3 / Drivers / STM32F3xx_HAL_Driver / Src / stm32f3xx_hal_irda.c
blob7c84358d73c1a7502cfd12ad0ef7513fba160547
1 /**
2 ******************************************************************************
3 * @file stm32f3xx_hal_irda.c
4 * @author MCD Application Team
5 * @brief IRDA HAL module driver.
6 * This file provides firmware functions to manage the following
7 * functionalities of the IrDA (Infrared Data Association) Peripheral
8 * (IRDA)
9 * + Initialization and de-initialization functions
10 * + IO operation functions
11 * + Peripheral State and Errors functions
12 * + Peripheral Control functions
14 @verbatim
15 ==============================================================================
16 ##### How to use this driver #####
17 ==============================================================================
18 [..]
19 The IRDA HAL driver can be used as follows:
21 (#) Declare a IRDA_HandleTypeDef handle structure (eg. IRDA_HandleTypeDef hirda).
22 (#) Initialize the IRDA low level resources by implementing the HAL_IRDA_MspInit() API
23 in setting the associated USART or UART in IRDA mode:
24 (++) Enable the USARTx/UARTx interface clock.
25 (++) USARTx/UARTx pins configuration:
26 (+++) Enable the clock for the USARTx/UARTx GPIOs.
27 (+++) Configure these USARTx/UARTx pins (TX as alternate function pull-up, RX as alternate function Input).
28 (++) NVIC configuration if you need to use interrupt process (HAL_IRDA_Transmit_IT()
29 and HAL_IRDA_Receive_IT() APIs):
30 (+++) Configure the USARTx/UARTx interrupt priority.
31 (+++) Enable the NVIC USARTx/UARTx IRQ handle.
32 (+++) The specific IRDA interrupts (Transmission complete interrupt,
33 RXNE interrupt and Error Interrupts) will be managed using the macros
34 __HAL_IRDA_ENABLE_IT() and __HAL_IRDA_DISABLE_IT() inside the transmit and receive process.
36 (++) DMA Configuration if you need to use DMA process (HAL_IRDA_Transmit_DMA()
37 and HAL_IRDA_Receive_DMA() APIs):
38 (+++) Declare a DMA handle structure for the Tx/Rx channel.
39 (+++) Enable the DMAx interface clock.
40 (+++) Configure the declared DMA handle structure with the required Tx/Rx parameters.
41 (+++) Configure the DMA Tx/Rx channel.
42 (+++) Associate the initialized DMA handle to the IRDA DMA Tx/Rx handle.
43 (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on the DMA Tx/Rx channel.
45 (#) Program the Baud Rate, Word Length and Parity and Mode(Receiver/Transmitter),
46 the normal or low power mode and the clock prescaler in the hirda handle Init structure.
48 (#) Initialize the IRDA registers by calling the HAL_IRDA_Init() API:
49 (++) This API configures also the low level Hardware (GPIO, CLOCK, CORTEX...etc)
50 by calling the customized HAL_IRDA_MspInit() API.
52 -@@- The specific IRDA interrupts (Transmission complete interrupt,
53 RXNE interrupt and Error Interrupts) will be managed using the macros
54 __HAL_IRDA_ENABLE_IT() and __HAL_IRDA_DISABLE_IT() inside the transmit and receive process.
56 (#) Three operation modes are available within this driver :
58 *** Polling mode IO operation ***
59 =================================
60 [..]
61 (+) Send an amount of data in blocking mode using HAL_IRDA_Transmit()
62 (+) Receive an amount of data in blocking mode using HAL_IRDA_Receive()
64 *** Interrupt mode IO operation ***
65 ===================================
66 [..]
67 (+) Send an amount of data in non-blocking mode using HAL_IRDA_Transmit_IT()
68 (+) At transmission end of transfer HAL_IRDA_TxCpltCallback() is executed and user can
69 add his own code by customization of function pointer HAL_IRDA_TxCpltCallback()
70 (+) Receive an amount of data in non-blocking mode using HAL_IRDA_Receive_IT()
71 (+) At reception end of transfer HAL_IRDA_RxCpltCallback() is executed and user can
72 add his own code by customization of function pointer HAL_IRDA_RxCpltCallback()
73 (+) In case of transfer Error, HAL_IRDA_ErrorCallback() function is executed and user can
74 add his own code by customization of function pointer HAL_IRDA_ErrorCallback()
76 *** DMA mode IO operation ***
77 ==============================
78 [..]
79 (+) Send an amount of data in non-blocking mode (DMA) using HAL_IRDA_Transmit_DMA()
80 (+) At transmission half of transfer HAL_IRDA_TxHalfCpltCallback() is executed and user can
81 add his own code by customization of function pointer HAL_IRDA_TxHalfCpltCallback()
82 (+) At transmission end of transfer HAL_IRDA_TxCpltCallback() is executed and user can
83 add his own code by customization of function pointer HAL_IRDA_TxCpltCallback()
84 (+) Receive an amount of data in non-blocking mode (DMA) using HAL_IRDA_Receive_DMA()
85 (+) At reception half of transfer HAL_IRDA_RxHalfCpltCallback() is executed and user can
86 add his own code by customization of function pointer HAL_IRDA_RxHalfCpltCallback()
87 (+) At reception end of transfer HAL_IRDA_RxCpltCallback() is executed and user can
88 add his own code by customization of function pointer HAL_IRDA_RxCpltCallback()
89 (+) In case of transfer Error, HAL_IRDA_ErrorCallback() function is executed and user can
90 add his own code by customization of function pointer HAL_IRDA_ErrorCallback()
92 *** IRDA HAL driver macros list ***
93 ====================================
94 [..]
95 Below the list of most used macros in IRDA HAL driver.
97 (+) __HAL_IRDA_ENABLE: Enable the IRDA peripheral
98 (+) __HAL_IRDA_DISABLE: Disable the IRDA peripheral
99 (+) __HAL_IRDA_GET_FLAG : Check whether the specified IRDA flag is set or not
100 (+) __HAL_IRDA_CLEAR_FLAG : Clear the specified IRDA pending flag
101 (+) __HAL_IRDA_ENABLE_IT: Enable the specified IRDA interrupt
102 (+) __HAL_IRDA_DISABLE_IT: Disable the specified IRDA interrupt
103 (+) __HAL_IRDA_GET_IT_SOURCE: Check whether or not the specified IRDA interrupt is enabled
105 [..]
106 (@) You can refer to the IRDA HAL driver header file for more useful macros
108 @endverbatim
109 ******************************************************************************
110 * @attention
112 * <h2><center>&copy; COPYRIGHT(c) 2016 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 "stm32f3xx_hal.h"
142 /** @addtogroup STM32F3xx_HAL_Driver
143 * @{
146 /** @defgroup IRDA IRDA
147 * @brief IRDA HAL module driver
148 * @{
151 #ifdef HAL_IRDA_MODULE_ENABLED
153 /* Private typedef -----------------------------------------------------------*/
154 /* Private define ------------------------------------------------------------*/
155 /** @defgroup IRDA_Private_Constants IRDA Private Constants
156 * @{
158 #define IRDA_TEACK_REACK_TIMEOUT 1000 /*!< IRDA TX or RX enable acknowledge time-out value */
159 #define IRDA_CR1_FIELDS ((uint32_t)(USART_CR1_M | USART_CR1_PCE \
160 | USART_CR1_PS | USART_CR1_TE | USART_CR1_RE)) /*!< UART or USART CR1 fields of parameters set by IRDA_SetConfig API */
162 * @}
165 /* Private macros ------------------------------------------------------------*/
166 /* Private variables ---------------------------------------------------------*/
167 /* Private function prototypes -----------------------------------------------*/
168 /** @addtogroup IRDA_Private_Functions
169 * @{
171 static HAL_StatusTypeDef IRDA_SetConfig(IRDA_HandleTypeDef *hirda);
172 static HAL_StatusTypeDef IRDA_CheckIdleState(IRDA_HandleTypeDef *hirda);
173 static HAL_StatusTypeDef IRDA_WaitOnFlagUntilTimeout(IRDA_HandleTypeDef *hirda, uint32_t Flag, FlagStatus Status, uint32_t Tickstart, uint32_t Timeout);
174 static void IRDA_EndTxTransfer(IRDA_HandleTypeDef *hirda);
175 static void IRDA_EndRxTransfer(IRDA_HandleTypeDef *hirda);
176 static void IRDA_DMATransmitCplt(DMA_HandleTypeDef *hdma);
177 static void IRDA_DMATransmitHalfCplt(DMA_HandleTypeDef *hdma);
178 static void IRDA_DMAReceiveCplt(DMA_HandleTypeDef *hdma);
179 static void IRDA_DMAReceiveHalfCplt(DMA_HandleTypeDef *hdma);
180 static void IRDA_DMAError(DMA_HandleTypeDef *hdma);
181 static void IRDA_DMAAbortOnError(DMA_HandleTypeDef *hdma);
182 static void IRDA_DMATxAbortCallback(DMA_HandleTypeDef *hdma);
183 static void IRDA_DMARxAbortCallback(DMA_HandleTypeDef *hdma);
184 static void IRDA_DMATxOnlyAbortCallback(DMA_HandleTypeDef *hdma);
185 static void IRDA_DMARxOnlyAbortCallback(DMA_HandleTypeDef *hdma);
186 static HAL_StatusTypeDef IRDA_Transmit_IT(IRDA_HandleTypeDef *hirda);
187 static HAL_StatusTypeDef IRDA_EndTransmit_IT(IRDA_HandleTypeDef *hirda);
188 static HAL_StatusTypeDef IRDA_Receive_IT(IRDA_HandleTypeDef *hirda);
190 * @}
193 /* Exported functions --------------------------------------------------------*/
195 /** @defgroup IRDA_Exported_Functions IRDA Exported Functions
196 * @{
199 /** @defgroup IRDA_Exported_Functions_Group1 Initialization and de-initialization functions
200 * @brief Initialization and Configuration functions
202 @verbatim
203 ==============================================================================
204 ##### Initialization and Configuration functions #####
205 ==============================================================================
206 [..]
207 This subsection provides a set of functions allowing to initialize the USARTx
208 in asynchronous IRDA mode.
209 (+) For the asynchronous mode only these parameters can be configured:
210 (++) Baud Rate
211 (++) Word Length
212 (++) Parity
213 (++) Power mode
214 (++) Prescaler setting
215 (++) Receiver/transmitter modes
217 [..]
218 The HAL_IRDA_Init() API follows the USART asynchronous configuration procedures
219 (details for the procedures are available in reference manual).
221 @endverbatim
222 * @{
226 Additional remark: If the parity is enabled, then the MSB bit of the data written
227 in the data register is transmitted but is changed by the parity bit.
228 According to device capability (support or not of 7-bit word length),
229 frame length is either defined by the M bit (8-bits or 9-bits)
230 or by the M1 and M0 bits (7-bit, 8-bit or 9-bit).
231 Possible IRDA frame formats are as listed in the following table:
233 Table 1. IRDA frame format.
234 +-----------------------------------------------------------------------+
235 | M bit | PCE bit | IRDA frame |
236 |-------------------|-----------|---------------------------------------|
237 | 0 | 0 | | SB | 8-bit data | STB | |
238 |-------------------|-----------|---------------------------------------|
239 | 0 | 1 | | SB | 7-bit data | PB | STB | |
240 |-------------------|-----------|---------------------------------------|
241 | 1 | 0 | | SB | 9-bit data | STB | |
242 |-------------------|-----------|---------------------------------------|
243 | 1 | 1 | | SB | 8-bit data | PB | STB | |
244 +-----------------------------------------------------------------------+
245 | M1 bit | M0 bit | PCE bit | IRDA frame |
246 |---------|---------|-----------|---------------------------------------|
247 | 0 | 0 | 0 | | SB | 8 bit data | STB | |
248 |---------|---------|-----------|---------------------------------------|
249 | 0 | 0 | 1 | | SB | 7 bit data | PB | STB | |
250 |---------|---------|-----------|---------------------------------------|
251 | 0 | 1 | 0 | | SB | 9 bit data | STB | |
252 |---------|---------|-----------|---------------------------------------|
253 | 0 | 1 | 1 | | SB | 8 bit data | PB | STB | |
254 |---------|---------|-----------|---------------------------------------|
255 | 1 | 0 | 0 | | SB | 7 bit data | STB | |
256 |---------|---------|-----------|---------------------------------------|
257 | 1 | 0 | 1 | | SB | 6 bit data | PB | STB | |
258 +-----------------------------------------------------------------------+
263 * @brief Initialize the IRDA mode according to the specified
264 * parameters in the IRDA_InitTypeDef and initialize the associated handle.
265 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
266 * the configuration information for the specified IRDA module.
267 * @retval HAL status
269 HAL_StatusTypeDef HAL_IRDA_Init(IRDA_HandleTypeDef *hirda)
271 /* Check the IRDA handle allocation */
272 if(hirda == NULL)
274 return HAL_ERROR;
277 /* Check the USART/UART associated to the IRDA handle */
278 assert_param(IS_IRDA_INSTANCE(hirda->Instance));
280 if(hirda->gState == HAL_IRDA_STATE_RESET)
282 /* Allocate lock resource and initialize it */
283 hirda->Lock = HAL_UNLOCKED;
285 /* Init the low level hardware : GPIO, CLOCK */
286 HAL_IRDA_MspInit(hirda);
289 hirda->gState = HAL_IRDA_STATE_BUSY;
291 /* Disable the Peripheral to update the configuration registers */
292 __HAL_IRDA_DISABLE(hirda);
294 /* Set the IRDA Communication parameters */
295 if (IRDA_SetConfig(hirda) == HAL_ERROR)
297 return HAL_ERROR;
300 /* In IRDA mode, the following bits must be kept cleared:
301 - LINEN, STOP and CLKEN bits in the USART_CR2 register,
302 - SCEN and HDSEL bits in the USART_CR3 register.*/
303 CLEAR_BIT(hirda->Instance->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN | USART_CR2_STOP));
304 CLEAR_BIT(hirda->Instance->CR3, (USART_CR3_SCEN | USART_CR3_HDSEL));
306 /* set the UART/USART in IRDA mode */
307 hirda->Instance->CR3 |= USART_CR3_IREN;
309 /* Enable the Peripheral */
310 __HAL_IRDA_ENABLE(hirda);
312 /* TEACK and/or REACK to check before moving hirda->gState and hirda->RxState to Ready */
313 return (IRDA_CheckIdleState(hirda));
317 * @brief DeInitialize the IRDA peripheral.
318 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
319 * the configuration information for the specified IRDA module.
320 * @retval HAL status
322 HAL_StatusTypeDef HAL_IRDA_DeInit(IRDA_HandleTypeDef *hirda)
324 /* Check the IRDA handle allocation */
325 if(hirda == NULL)
327 return HAL_ERROR;
330 /* Check the USART/UART associated to the IRDA handle */
331 assert_param(IS_IRDA_INSTANCE(hirda->Instance));
333 hirda->gState = HAL_IRDA_STATE_BUSY;
335 /* DeInit the low level hardware */
336 HAL_IRDA_MspDeInit(hirda);
337 /* Disable the Peripheral */
338 __HAL_IRDA_DISABLE(hirda);
340 hirda->ErrorCode = HAL_IRDA_ERROR_NONE;
341 hirda->gState = HAL_IRDA_STATE_RESET;
342 hirda->RxState = HAL_IRDA_STATE_RESET;
344 /* Process Unlock */
345 __HAL_UNLOCK(hirda);
347 return HAL_OK;
351 * @brief Initialize the IRDA MSP.
352 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
353 * the configuration information for the specified IRDA module.
354 * @retval None
356 __weak void HAL_IRDA_MspInit(IRDA_HandleTypeDef *hirda)
358 /* Prevent unused argument(s) compilation warning */
359 UNUSED(hirda);
361 /* NOTE: This function should not be modified, when the callback is needed,
362 the HAL_IRDA_MspInit can be implemented in the user file
367 * @brief DeInitialize the IRDA MSP.
368 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
369 * the configuration information for the specified IRDA module.
370 * @retval None
372 __weak void HAL_IRDA_MspDeInit(IRDA_HandleTypeDef *hirda)
374 /* Prevent unused argument(s) compilation warning */
375 UNUSED(hirda);
377 /* NOTE: This function should not be modified, when the callback is needed,
378 the HAL_IRDA_MspDeInit can be implemented in the user file
383 * @}
386 /** @defgroup IRDA_Exported_Functions_Group2 IO operation functions
387 * @brief IRDA Transmit and Receive functions
389 @verbatim
390 ===============================================================================
391 ##### IO operation functions #####
392 ===============================================================================
393 [..]
394 This subsection provides a set of functions allowing to manage the IRDA data transfers.
396 [..]
397 IrDA is a half duplex communication protocol. If the Transmitter is busy, any data
398 on the IrDA receive line will be ignored by the IrDA decoder and if the Receiver
399 is busy, data on the TX from the USART to IrDA will not be encoded by IrDA.
400 While receiving data, transmission should be avoided as the data to be transmitted
401 could be corrupted.
403 (#) There are two mode of transfer:
404 (++) Blocking mode: the communication is performed in polling mode.
405 The HAL status of all data processing is returned by the same function
406 after finishing transfer.
407 (++) Non-Blocking mode: the communication is performed using Interrupts
408 or DMA, these API's return the HAL status.
409 The end of the data processing will be indicated through the
410 dedicated IRDA IRQ when using Interrupt mode or the DMA IRQ when
411 using DMA mode.
412 The HAL_IRDA_TxCpltCallback(), HAL_IRDA_RxCpltCallback() user callbacks
413 will be executed respectively at the end of the Transmit or Receive process
414 The HAL_IRDA_ErrorCallback() user callback will be executed when a communication error is detected
416 (#) Blocking mode APIs are :
417 (++) HAL_IRDA_Transmit()
418 (++) HAL_IRDA_Receive()
420 (#) Non Blocking mode APIs with Interrupt are :
421 (++) HAL_IRDA_Transmit_IT()
422 (++) HAL_IRDA_Receive_IT()
423 (++) HAL_IRDA_IRQHandler()
425 (#) Non Blocking mode functions with DMA are :
426 (++) HAL_IRDA_Transmit_DMA()
427 (++) HAL_IRDA_Receive_DMA()
428 (++) HAL_IRDA_DMAPause()
429 (++) HAL_IRDA_DMAResume()
430 (++) HAL_IRDA_DMAStop()
432 (#) A set of Transfer Complete Callbacks are provided in Non Blocking mode:
433 (++) HAL_IRDA_TxHalfCpltCallback()
434 (++) HAL_IRDA_TxCpltCallback()
435 (++) HAL_IRDA_RxHalfCpltCallback()
436 (++) HAL_IRDA_RxCpltCallback()
437 (++) HAL_IRDA_ErrorCallback()
439 (#) Non-Blocking mode transfers could be aborted using Abort API's :
440 (++) HAL_IRDA_Abort()
441 (++) HAL_IRDA_AbortTransmit()
442 (++) HAL_IRDA_AbortReceive()
443 (++) HAL_IRDA_Abort_IT()
444 (++) HAL_IRDA_AbortTransmit_IT()
445 (++) HAL_IRDA_AbortReceive_IT()
447 (#) For Abort services based on interrupts (HAL_IRDA_Abortxxx_IT), a set of Abort Complete Callbacks are provided:
448 (++) HAL_IRDA_AbortCpltCallback()
449 (++) HAL_IRDA_AbortTransmitCpltCallback()
450 (++) HAL_IRDA_AbortReceiveCpltCallback()
452 (#) In Non-Blocking mode transfers, possible errors are split into 2 categories.
453 Errors are handled as follows :
454 (++) Error is considered as Recoverable and non blocking : Transfer could go till end, but error severity is
455 to be evaluated by user : this concerns Frame Error, Parity Error or Noise Error in Interrupt mode reception .
456 Received character is then retrieved and stored in Rx buffer, Error code is set to allow user to identify error type,
457 and HAL_IRDA_ErrorCallback() user callback is executed. Transfer is kept ongoing on IRDA side.
458 If user wants to abort it, Abort services should be called by user.
459 (++) Error is considered as Blocking : Transfer could not be completed properly and is aborted.
460 This concerns Overrun Error In Interrupt mode reception and all errors in DMA mode.
461 Error code is set to allow user to identify error type, and HAL_IRDA_ErrorCallback() user callback is executed.
463 @endverbatim
464 * @{
468 * @brief Send an amount of data in blocking mode.
469 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
470 * the configuration information for the specified IRDA module.
471 * @param pData Pointer to data buffer.
472 * @param Size Amount of data to be sent.
473 * @param Timeout Specify timeout value.
474 * @retval HAL status
476 HAL_StatusTypeDef HAL_IRDA_Transmit(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size, uint32_t Timeout)
478 uint16_t* tmp;
479 uint32_t tickstart = 0U;
481 /* Check that a Tx process is not already ongoing */
482 if(hirda->gState == HAL_IRDA_STATE_READY)
484 if((pData == NULL) || (Size == 0U))
486 return HAL_ERROR;
489 /* Process Locked */
490 __HAL_LOCK(hirda);
492 hirda->ErrorCode = HAL_IRDA_ERROR_NONE;
493 hirda->gState = HAL_IRDA_STATE_BUSY_TX;
495 /* Init tickstart for timeout managment*/
496 tickstart = HAL_GetTick();
498 hirda->TxXferSize = Size;
499 hirda->TxXferCount = Size;
500 while(hirda->TxXferCount > 0U)
502 hirda->TxXferCount--;
504 if(IRDA_WaitOnFlagUntilTimeout(hirda, IRDA_FLAG_TXE, RESET, tickstart, Timeout) != HAL_OK)
506 return HAL_TIMEOUT;
508 if ((hirda->Init.WordLength == IRDA_WORDLENGTH_9B) && (hirda->Init.Parity == IRDA_PARITY_NONE))
510 tmp = (uint16_t*) pData;
511 hirda->Instance->TDR = (*tmp & (uint16_t)0x01FFU);
512 pData += 2U;
514 else
516 hirda->Instance->TDR = (*pData++ & (uint8_t)0xFFU);
520 if(IRDA_WaitOnFlagUntilTimeout(hirda, IRDA_FLAG_TC, RESET, tickstart, Timeout) != HAL_OK)
522 return HAL_TIMEOUT;
525 /* At end of Tx process, restore hirda->gState to Ready */
526 hirda->gState = HAL_IRDA_STATE_READY;
528 /* Process Unlocked */
529 __HAL_UNLOCK(hirda);
531 return HAL_OK;
533 else
535 return HAL_BUSY;
540 * @brief Receive an amount of data in blocking mode.
541 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
542 * the configuration information for the specified IRDA module.
543 * @param pData Pointer to data buffer.
544 * @param Size Amount of data to be received.
545 * @param Timeout Specify timeout value.
546 * @retval HAL status
548 HAL_StatusTypeDef HAL_IRDA_Receive(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size, uint32_t Timeout)
550 uint16_t* tmp;
551 uint16_t uhMask;
552 uint32_t tickstart = 0U;
554 /* Check that a Rx process is not already ongoing */
555 if(hirda->RxState == HAL_IRDA_STATE_READY)
557 if((pData == NULL) || (Size == 0U))
559 return HAL_ERROR;
562 /* Process Locked */
563 __HAL_LOCK(hirda);
565 hirda->ErrorCode = HAL_IRDA_ERROR_NONE;
566 hirda->RxState = HAL_IRDA_STATE_BUSY_RX;
568 /* Init tickstart for timeout managment*/
569 tickstart = HAL_GetTick();
571 hirda->RxXferSize = Size;
572 hirda->RxXferCount = Size;
574 /* Computation of the mask to apply to RDR register
575 of the UART associated to the IRDA */
576 IRDA_MASK_COMPUTATION(hirda);
577 uhMask = hirda->Mask;
579 /* Check data remaining to be received */
580 while(hirda->RxXferCount > 0U)
582 hirda->RxXferCount--;
584 if(IRDA_WaitOnFlagUntilTimeout(hirda, IRDA_FLAG_RXNE, RESET, tickstart, Timeout) != HAL_OK)
586 return HAL_TIMEOUT;
588 if ((hirda->Init.WordLength == IRDA_WORDLENGTH_9B) && (hirda->Init.Parity == IRDA_PARITY_NONE))
590 tmp = (uint16_t*) pData ;
591 *tmp = (uint16_t)(hirda->Instance->RDR & uhMask);
592 pData +=2U;
594 else
596 *pData++ = (uint8_t)(hirda->Instance->RDR & (uint8_t)uhMask);
600 /* At end of Rx process, restore hirda->RxState to Ready */
601 hirda->RxState = HAL_IRDA_STATE_READY;
603 /* Process Unlocked */
604 __HAL_UNLOCK(hirda);
606 return HAL_OK;
608 else
610 return HAL_BUSY;
615 * @brief Send an amount of data in interrupt mode.
616 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
617 * the configuration information for the specified IRDA module.
618 * @param pData Pointer to data buffer.
619 * @param Size Amount of data to be sent.
620 * @retval HAL status
622 HAL_StatusTypeDef HAL_IRDA_Transmit_IT(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size)
624 /* Check that a Tx process is not already ongoing */
625 if(hirda->gState == HAL_IRDA_STATE_READY)
627 if((pData == NULL) || (Size == 0U))
629 return HAL_ERROR;
632 /* Process Locked */
633 __HAL_LOCK(hirda);
635 hirda->pTxBuffPtr = pData;
636 hirda->TxXferSize = Size;
637 hirda->TxXferCount = Size;
639 hirda->ErrorCode = HAL_IRDA_ERROR_NONE;
640 hirda->gState = HAL_IRDA_STATE_BUSY_TX;
642 /* Process Unlocked */
643 __HAL_UNLOCK(hirda);
645 /* Enable the IRDA Transmit Data Register Empty Interrupt */
646 SET_BIT(hirda->Instance->CR1, USART_CR1_TXEIE);
648 return HAL_OK;
650 else
652 return HAL_BUSY;
657 * @brief Receive an amount of data in interrupt mode.
658 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
659 * the configuration information for the specified IRDA module.
660 * @param pData Pointer to data buffer.
661 * @param Size Amount of data to be received.
662 * @retval HAL status
664 HAL_StatusTypeDef HAL_IRDA_Receive_IT(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size)
666 /* Check that a Rx process is not already ongoing */
667 if(hirda->RxState == HAL_IRDA_STATE_READY)
669 if((pData == NULL) || (Size == 0U))
671 return HAL_ERROR;
674 /* Process Locked */
675 __HAL_LOCK(hirda);
677 hirda->pRxBuffPtr = pData;
678 hirda->RxXferSize = Size;
679 hirda->RxXferCount = Size;
681 /* Computation of the mask to apply to the RDR register
682 of the UART associated to the IRDA */
683 IRDA_MASK_COMPUTATION(hirda);
685 hirda->ErrorCode = HAL_IRDA_ERROR_NONE;
686 hirda->RxState = HAL_IRDA_STATE_BUSY_RX;
688 /* Process Unlocked */
689 __HAL_UNLOCK(hirda);
691 /* Enable the IRDA Parity Error and Data Register not empty Interrupts */
692 SET_BIT(hirda->Instance->CR1, USART_CR1_PEIE| USART_CR1_RXNEIE);
694 /* Enable the IRDA Error Interrupt: (Frame error, noise error, overrun error) */
695 SET_BIT(hirda->Instance->CR3, USART_CR3_EIE);
697 return HAL_OK;
699 else
701 return HAL_BUSY;
706 * @brief Send an amount of data in DMA mode.
707 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
708 * the configuration information for the specified IRDA module.
709 * @param pData pointer to data buffer.
710 * @param Size amount of data to be sent.
711 * @retval HAL status
713 HAL_StatusTypeDef HAL_IRDA_Transmit_DMA(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size)
715 /* Check if USART/UART instance associated to the IRDA handle supports continuous communication using DMA */
716 assert_param(IS_UART_DMA_INSTANCE(hirda->Instance));
718 /* Check that a Tx process is not already ongoing */
719 if(hirda->gState == HAL_IRDA_STATE_READY)
721 if((pData == NULL) || (Size == 0U))
723 return HAL_ERROR;
726 /* Process Locked */
727 __HAL_LOCK(hirda);
729 hirda->pTxBuffPtr = pData;
730 hirda->TxXferSize = Size;
731 hirda->TxXferCount = Size;
733 hirda->ErrorCode = HAL_IRDA_ERROR_NONE;
734 hirda->gState = HAL_IRDA_STATE_BUSY_TX;
736 /* Set the IRDA DMA transfer complete callback */
737 hirda->hdmatx->XferCpltCallback = IRDA_DMATransmitCplt;
739 /* Set the IRDA DMA half transfer complete callback */
740 hirda->hdmatx->XferHalfCpltCallback = IRDA_DMATransmitHalfCplt;
742 /* Set the DMA error callback */
743 hirda->hdmatx->XferErrorCallback = IRDA_DMAError;
745 /* Set the DMA abort callback */
746 hirda->hdmatx->XferAbortCallback = NULL;
748 /* Enable the IRDA transmit DMA channel */
749 HAL_DMA_Start_IT(hirda->hdmatx, (uint32_t)hirda->pTxBuffPtr, (uint32_t)&hirda->Instance->TDR, Size);
751 /* Clear the TC flag in the ICR register */
752 __HAL_IRDA_CLEAR_FLAG(hirda, IRDA_CLEAR_TCF);
754 /* Process Unlocked */
755 __HAL_UNLOCK(hirda);
757 /* Enable the DMA transfer for transmit request by setting the DMAT bit
758 in the USART CR3 register */
759 SET_BIT(hirda->Instance->CR3, USART_CR3_DMAT);
761 return HAL_OK;
763 else
765 return HAL_BUSY;
770 * @brief Receive an amount of data in DMA mode.
771 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
772 * the configuration information for the specified IRDA module.
773 * @param pData Pointer to data buffer.
774 * @param Size Amount of data to be received.
775 * @note When the IRDA parity is enabled (PCE = 1), the received data contains
776 * the parity bit (MSB position).
777 * @retval HAL status
779 HAL_StatusTypeDef HAL_IRDA_Receive_DMA(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size)
781 /* Check if USART/UART instance associated to the IRDA handle supports continuous communication using DMA */
782 assert_param(IS_UART_DMA_INSTANCE(hirda->Instance));
784 /* Check that a Rx process is not already ongoing */
785 if(hirda->RxState == HAL_IRDA_STATE_READY)
787 if((pData == NULL) || (Size == 0U))
789 return HAL_ERROR;
792 /* Process Locked */
793 __HAL_LOCK(hirda);
795 hirda->pRxBuffPtr = pData;
796 hirda->RxXferSize = Size;
798 hirda->ErrorCode = HAL_IRDA_ERROR_NONE;
799 hirda->RxState = HAL_IRDA_STATE_BUSY_RX;
801 /* Set the IRDA DMA transfer complete callback */
802 hirda->hdmarx->XferCpltCallback = IRDA_DMAReceiveCplt;
804 /* Set the IRDA DMA half transfer complete callback */
805 hirda->hdmarx->XferHalfCpltCallback = IRDA_DMAReceiveHalfCplt;
807 /* Set the DMA error callback */
808 hirda->hdmarx->XferErrorCallback = IRDA_DMAError;
810 /* Set the DMA abort callback */
811 hirda->hdmarx->XferAbortCallback = NULL;
813 /* Enable the DMA channel */
814 HAL_DMA_Start_IT(hirda->hdmarx, (uint32_t)&hirda->Instance->RDR, (uint32_t)hirda->pRxBuffPtr, Size);
816 /* Process Unlocked */
817 __HAL_UNLOCK(hirda);
819 /* Enable the UART Parity Error Interrupt */
820 SET_BIT(hirda->Instance->CR1, USART_CR1_PEIE);
822 /* Enable the UART Error Interrupt: (Frame error, noise error, overrun error) */
823 SET_BIT(hirda->Instance->CR3, USART_CR3_EIE);
825 /* Enable the DMA transfer for the receiver request by setting the DMAR bit
826 in the USART CR3 register */
827 SET_BIT(hirda->Instance->CR3, USART_CR3_DMAR);
829 return HAL_OK;
831 else
833 return HAL_BUSY;
839 * @brief Pause the DMA Transfer.
840 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
841 * the configuration information for the specified IRDA module.
842 * @retval HAL status
844 HAL_StatusTypeDef HAL_IRDA_DMAPause(IRDA_HandleTypeDef *hirda)
846 /* Process Locked */
847 __HAL_LOCK(hirda);
849 if ((hirda->gState == HAL_IRDA_STATE_BUSY_TX) &&
850 (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAT)))
852 /* Disable the IRDA DMA Tx request */
853 CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAT);
855 if ((hirda->RxState == HAL_IRDA_STATE_BUSY_RX) &&
856 (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAR)))
858 /* Disable PE and ERR (Frame error, noise error, overrun error) interrupts */
859 CLEAR_BIT(hirda->Instance->CR1, USART_CR1_PEIE);
860 CLEAR_BIT(hirda->Instance->CR3, USART_CR3_EIE);
862 /* Disable the IRDA DMA Rx request */
863 CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAR);
866 /* Process Unlocked */
867 __HAL_UNLOCK(hirda);
869 return HAL_OK;
873 * @brief Resume the DMA Transfer.
874 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
875 * the configuration information for the specified UART module.
876 * @retval HAL status
878 HAL_StatusTypeDef HAL_IRDA_DMAResume(IRDA_HandleTypeDef *hirda)
880 /* Process Locked */
881 __HAL_LOCK(hirda);
883 if(hirda->gState == HAL_IRDA_STATE_BUSY_TX)
885 /* Enable the IRDA DMA Tx request */
886 SET_BIT(hirda->Instance->CR3, USART_CR3_DMAT);
888 if(hirda->RxState == HAL_IRDA_STATE_BUSY_RX)
890 /* Clear the Overrun flag before resuming the Rx transfer*/
891 __HAL_IRDA_CLEAR_OREFLAG(hirda);
893 /* Reenable PE and ERR (Frame error, noise error, overrun error) interrupts */
894 SET_BIT(hirda->Instance->CR1, USART_CR1_PEIE);
895 SET_BIT(hirda->Instance->CR3, USART_CR3_EIE);
897 /* Enable the IRDA DMA Rx request */
898 SET_BIT(hirda->Instance->CR3, USART_CR3_DMAR);
901 /* Process Unlocked */
902 __HAL_UNLOCK(hirda);
904 return HAL_OK;
908 * @brief Stop the DMA Transfer.
909 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
910 * the configuration information for the specified UART module.
911 * @retval HAL status
913 HAL_StatusTypeDef HAL_IRDA_DMAStop(IRDA_HandleTypeDef *hirda)
915 /* The Lock is not implemented on this API to allow the user application
916 to call the HAL IRDA API under callbacks HAL_IRDA_TxCpltCallback() / HAL_IRDA_RxCpltCallback() /
917 HAL_IRDA_TxHalfCpltCallback() / HAL_IRDA_RxHalfCpltCallback():
918 indeed, when HAL_DMA_Abort() API is called, the DMA TX/RX Transfer or Half Transfer complete
919 interrupt is generated if the DMA transfer interruption occurs at the middle or at the end of
920 the stream and the corresponding call back is executed. */
922 /* Stop IRDA DMA Tx request if ongoing */
923 if ((hirda->gState == HAL_IRDA_STATE_BUSY_TX) &&
924 (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAT)))
926 CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAT);
928 /* Abort the IRDA DMA Tx channel */
929 if(hirda->hdmatx != NULL)
931 HAL_DMA_Abort(hirda->hdmatx);
934 IRDA_EndTxTransfer(hirda);
937 /* Stop IRDA DMA Rx request if ongoing */
938 if ((hirda->RxState == HAL_IRDA_STATE_BUSY_RX) &&
939 (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAR)))
941 CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAR);
943 /* Abort the IRDA DMA Rx channel */
944 if(hirda->hdmarx != NULL)
946 HAL_DMA_Abort(hirda->hdmarx);
949 IRDA_EndRxTransfer(hirda);
952 return HAL_OK;
956 * @brief Abort ongoing transfers (blocking mode).
957 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
958 * the configuration information for the specified UART module.
959 * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode.
960 * This procedure performs following operations :
961 * - Disable IRDA Interrupts (Tx and Rx)
962 * - Disable the DMA transfer in the peripheral register (if enabled)
963 * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode)
964 * - Set handle State to READY
965 * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed.
966 * @retval HAL status
968 HAL_StatusTypeDef HAL_IRDA_Abort(IRDA_HandleTypeDef *hirda)
970 /* Disable TXEIE, TCIE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */
971 CLEAR_BIT(hirda->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE));
972 CLEAR_BIT(hirda->Instance->CR3, USART_CR3_EIE);
974 /* Disable the IRDA DMA Tx request if enabled */
975 if (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAT))
977 CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAT);
979 /* Abort the IRDA DMA Tx channel : use blocking DMA Abort API (no callback) */
980 if(hirda->hdmatx != NULL)
982 /* Set the IRDA DMA Abort callback to Null.
983 No call back execution at end of DMA abort procedure */
984 hirda->hdmatx->XferAbortCallback = NULL;
986 HAL_DMA_Abort(hirda->hdmatx);
990 /* Disable the IRDA DMA Rx request if enabled */
991 if (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAR))
993 CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAR);
995 /* Abort the IRDA DMA Rx channel : use blocking DMA Abort API (no callback) */
996 if(hirda->hdmarx != NULL)
998 /* Set the IRDA DMA Abort callback to Null.
999 No call back execution at end of DMA abort procedure */
1000 hirda->hdmarx->XferAbortCallback = NULL;
1002 HAL_DMA_Abort(hirda->hdmarx);
1006 /* Reset Tx and Rx transfer counters */
1007 hirda->TxXferCount = 0U;
1008 hirda->RxXferCount = 0U;
1010 /* Clear the Error flags in the ICR register */
1011 __HAL_IRDA_CLEAR_FLAG(hirda, IRDA_CLEAR_OREF | IRDA_CLEAR_NEF | IRDA_CLEAR_PEF | IRDA_CLEAR_FEF);
1013 /* Restore hirda->gState and hirda->RxState to Ready */
1014 hirda->gState = HAL_IRDA_STATE_READY;
1015 hirda->RxState = HAL_IRDA_STATE_READY;
1017 /* Reset Handle ErrorCode to No Error */
1018 hirda->ErrorCode = HAL_IRDA_ERROR_NONE;
1020 return HAL_OK;
1024 * @brief Abort ongoing Transmit transfer (blocking mode).
1025 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
1026 * the configuration information for the specified UART module.
1027 * @note This procedure could be used for aborting any ongoing Tx transfer started in Interrupt or DMA mode.
1028 * This procedure performs following operations :
1029 * - Disable IRDA Interrupts (Tx)
1030 * - Disable the DMA transfer in the peripheral register (if enabled)
1031 * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode)
1032 * - Set handle State to READY
1033 * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed.
1034 * @retval HAL status
1036 HAL_StatusTypeDef HAL_IRDA_AbortTransmit(IRDA_HandleTypeDef *hirda)
1038 /* Disable TXEIE and TCIE interrupts */
1039 CLEAR_BIT(hirda->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE));
1041 /* Disable the IRDA DMA Tx request if enabled */
1042 if (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAT))
1044 CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAT);
1046 /* Abort the IRDA DMA Tx channel : use blocking DMA Abort API (no callback) */
1047 if(hirda->hdmatx != NULL)
1049 /* Set the IRDA DMA Abort callback to Null.
1050 No call back execution at end of DMA abort procedure */
1051 hirda->hdmatx->XferAbortCallback = NULL;
1053 HAL_DMA_Abort(hirda->hdmatx);
1057 /* Reset Tx transfer counter */
1058 hirda->TxXferCount = 0U;
1060 /* Restore hirda->gState to Ready */
1061 hirda->gState = HAL_IRDA_STATE_READY;
1063 return HAL_OK;
1067 * @brief Abort ongoing Receive transfer (blocking mode).
1068 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
1069 * the configuration information for the specified UART module.
1070 * @note This procedure could be used for aborting any ongoing Rx transfer started in Interrupt or DMA mode.
1071 * This procedure performs following operations :
1072 * - Disable IRDA Interrupts (Rx)
1073 * - Disable the DMA transfer in the peripheral register (if enabled)
1074 * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode)
1075 * - Set handle State to READY
1076 * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed.
1077 * @retval HAL status
1079 HAL_StatusTypeDef HAL_IRDA_AbortReceive(IRDA_HandleTypeDef *hirda)
1081 /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */
1082 CLEAR_BIT(hirda->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE));
1083 CLEAR_BIT(hirda->Instance->CR3, USART_CR3_EIE);
1085 /* Disable the IRDA DMA Rx request if enabled */
1086 if (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAR))
1088 CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAR);
1090 /* Abort the IRDA DMA Rx channel : use blocking DMA Abort API (no callback) */
1091 if(hirda->hdmarx != NULL)
1093 /* Set the IRDA DMA Abort callback to Null.
1094 No call back execution at end of DMA abort procedure */
1095 hirda->hdmarx->XferAbortCallback = NULL;
1097 HAL_DMA_Abort(hirda->hdmarx);
1101 /* Reset Rx transfer counter */
1102 hirda->RxXferCount = 0U;
1104 /* Clear the Error flags in the ICR register */
1105 __HAL_IRDA_CLEAR_FLAG(hirda, IRDA_CLEAR_OREF | IRDA_CLEAR_NEF | IRDA_CLEAR_PEF | IRDA_CLEAR_FEF);
1107 /* Restore hirda->RxState to Ready */
1108 hirda->RxState = HAL_IRDA_STATE_READY;
1110 return HAL_OK;
1114 * @brief Abort ongoing transfers (Interrupt mode).
1115 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
1116 * the configuration information for the specified UART module.
1117 * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode.
1118 * This procedure performs following operations :
1119 * - Disable IRDA Interrupts (Tx and Rx)
1120 * - Disable the DMA transfer in the peripheral register (if enabled)
1121 * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode)
1122 * - Set handle State to READY
1123 * - At abort completion, call user abort complete callback
1124 * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be
1125 * considered as completed only when user abort complete callback is executed (not when exiting function).
1126 * @retval HAL status
1128 HAL_StatusTypeDef HAL_IRDA_Abort_IT(IRDA_HandleTypeDef *hirda)
1130 uint32_t abortcplt = 1U;
1132 /* Disable TXEIE, TCIE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */
1133 CLEAR_BIT(hirda->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE));
1134 CLEAR_BIT(hirda->Instance->CR3, USART_CR3_EIE);
1136 /* If DMA Tx and/or DMA Rx Handles are associated to IRDA Handle, DMA Abort complete callbacks should be initialised
1137 before any call to DMA Abort functions */
1138 /* DMA Tx Handle is valid */
1139 if(hirda->hdmatx != NULL)
1141 /* Set DMA Abort Complete callback if IRDA DMA Tx request if enabled.
1142 Otherwise, set it to NULL */
1143 if(HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAT))
1145 hirda->hdmatx->XferAbortCallback = IRDA_DMATxAbortCallback;
1147 else
1149 hirda->hdmatx->XferAbortCallback = NULL;
1152 /* DMA Rx Handle is valid */
1153 if(hirda->hdmarx != NULL)
1155 /* Set DMA Abort Complete callback if IRDA DMA Rx request if enabled.
1156 Otherwise, set it to NULL */
1157 if(HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAR))
1159 hirda->hdmarx->XferAbortCallback = IRDA_DMARxAbortCallback;
1161 else
1163 hirda->hdmarx->XferAbortCallback = NULL;
1167 /* Disable the IRDA DMA Tx request if enabled */
1168 if(HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAT))
1170 /* Disable DMA Tx at UART level */
1171 CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAT);
1173 /* Abort the IRDA DMA Tx channel : use non blocking DMA Abort API (callback) */
1174 if(hirda->hdmatx != NULL)
1176 /* IRDA Tx DMA Abort callback has already been initialised :
1177 will lead to call HAL_IRDA_AbortCpltCallback() at end of DMA abort procedure */
1179 /* Abort DMA TX */
1180 if(HAL_DMA_Abort_IT(hirda->hdmatx) != HAL_OK)
1182 hirda->hdmatx->XferAbortCallback = NULL;
1184 else
1186 abortcplt = 0U;
1191 /* Disable the IRDA DMA Rx request if enabled */
1192 if (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAR))
1194 CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAR);
1196 /* Abort the IRDA DMA Rx channel : use non blocking DMA Abort API (callback) */
1197 if(hirda->hdmarx != NULL)
1199 /* IRDA Rx DMA Abort callback has already been initialised :
1200 will lead to call HAL_IRDA_AbortCpltCallback() at end of DMA abort procedure */
1202 /* Abort DMA RX */
1203 if(HAL_DMA_Abort_IT(hirda->hdmarx) != HAL_OK)
1205 hirda->hdmarx->XferAbortCallback = NULL;
1206 abortcplt = 1U;
1208 else
1210 abortcplt = 0U;
1215 /* if no DMA abort complete callback execution is required => call user Abort Complete callback */
1216 if (abortcplt == 1U)
1218 /* Reset Tx and Rx transfer counters */
1219 hirda->TxXferCount = 0U;
1220 hirda->RxXferCount = 0U;
1222 /* Reset errorCode */
1223 hirda->ErrorCode = HAL_IRDA_ERROR_NONE;
1225 /* Clear the Error flags in the ICR register */
1226 __HAL_IRDA_CLEAR_FLAG(hirda, IRDA_CLEAR_OREF | IRDA_CLEAR_NEF | IRDA_CLEAR_PEF | IRDA_CLEAR_FEF);
1228 /* Restore hirda->gState and hirda->RxState to Ready */
1229 hirda->gState = HAL_IRDA_STATE_READY;
1230 hirda->RxState = HAL_IRDA_STATE_READY;
1232 /* As no DMA to be aborted, call directly user Abort complete callback */
1233 HAL_IRDA_AbortCpltCallback(hirda);
1236 return HAL_OK;
1240 * @brief Abort ongoing Transmit transfer (Interrupt mode).
1241 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
1242 * the configuration information for the specified UART module.
1243 * @note This procedure could be used for aborting any ongoing Tx transfer started in Interrupt or DMA mode.
1244 * This procedure performs following operations :
1245 * - Disable IRDA Interrupts (Tx)
1246 * - Disable the DMA transfer in the peripheral register (if enabled)
1247 * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode)
1248 * - Set handle State to READY
1249 * - At abort completion, call user abort complete callback
1250 * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be
1251 * considered as completed only when user abort complete callback is executed (not when exiting function).
1252 * @retval HAL status
1254 HAL_StatusTypeDef HAL_IRDA_AbortTransmit_IT(IRDA_HandleTypeDef *hirda)
1256 /* Disable TXEIE and TCIE interrupts */
1257 CLEAR_BIT(hirda->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE));
1259 /* Disable the IRDA DMA Tx request if enabled */
1260 if (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAT))
1262 CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAT);
1264 /* Abort the IRDA DMA Tx channel : use non blocking DMA Abort API (callback) */
1265 if(hirda->hdmatx != NULL)
1267 /* Set the IRDA DMA Abort callback :
1268 will lead to call HAL_IRDA_AbortCpltCallback() at end of DMA abort procedure */
1269 hirda->hdmatx->XferAbortCallback = IRDA_DMATxOnlyAbortCallback;
1271 /* Abort DMA TX */
1272 if(HAL_DMA_Abort_IT(hirda->hdmatx) != HAL_OK)
1274 /* Call Directly hirda->hdmatx->XferAbortCallback function in case of error */
1275 hirda->hdmatx->XferAbortCallback(hirda->hdmatx);
1278 else
1280 /* Reset Tx transfer counter */
1281 hirda->TxXferCount = 0U;
1283 /* Restore hirda->gState to Ready */
1284 hirda->gState = HAL_IRDA_STATE_READY;
1286 /* As no DMA to be aborted, call directly user Abort complete callback */
1287 HAL_IRDA_AbortTransmitCpltCallback(hirda);
1290 else
1292 /* Reset Tx transfer counter */
1293 hirda->TxXferCount = 0U;
1295 /* Restore hirda->gState to Ready */
1296 hirda->gState = HAL_IRDA_STATE_READY;
1298 /* As no DMA to be aborted, call directly user Abort complete callback */
1299 HAL_IRDA_AbortTransmitCpltCallback(hirda);
1302 return HAL_OK;
1306 * @brief Abort ongoing Receive transfer (Interrupt mode).
1307 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
1308 * the configuration information for the specified UART module.
1309 * @note This procedure could be used for aborting any ongoing Rx transfer started in Interrupt or DMA mode.
1310 * This procedure performs following operations :
1311 * - Disable IRDA Interrupts (Rx)
1312 * - Disable the DMA transfer in the peripheral register (if enabled)
1313 * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode)
1314 * - Set handle State to READY
1315 * - At abort completion, call user abort complete callback
1316 * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be
1317 * considered as completed only when user abort complete callback is executed (not when exiting function).
1318 * @retval HAL status
1320 HAL_StatusTypeDef HAL_IRDA_AbortReceive_IT(IRDA_HandleTypeDef *hirda)
1322 /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */
1323 CLEAR_BIT(hirda->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE));
1324 CLEAR_BIT(hirda->Instance->CR3, USART_CR3_EIE);
1326 /* Disable the IRDA DMA Rx request if enabled */
1327 if (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAR))
1329 CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAR);
1331 /* Abort the IRDA DMA Rx channel : use non blocking DMA Abort API (callback) */
1332 if(hirda->hdmarx != NULL)
1334 /* Set the IRDA DMA Abort callback :
1335 will lead to call HAL_IRDA_AbortCpltCallback() at end of DMA abort procedure */
1336 hirda->hdmarx->XferAbortCallback = IRDA_DMARxOnlyAbortCallback;
1338 /* Abort DMA RX */
1339 if(HAL_DMA_Abort_IT(hirda->hdmarx) != HAL_OK)
1341 /* Call Directly hirda->hdmarx->XferAbortCallback function in case of error */
1342 hirda->hdmarx->XferAbortCallback(hirda->hdmarx);
1345 else
1347 /* Reset Rx transfer counter */
1348 hirda->RxXferCount = 0U;
1350 /* Clear the Error flags in the ICR register */
1351 __HAL_IRDA_CLEAR_FLAG(hirda, IRDA_CLEAR_OREF | IRDA_CLEAR_NEF | IRDA_CLEAR_PEF | IRDA_CLEAR_FEF);
1353 /* Restore hirda->RxState to Ready */
1354 hirda->RxState = HAL_IRDA_STATE_READY;
1356 /* As no DMA to be aborted, call directly user Abort complete callback */
1357 HAL_IRDA_AbortReceiveCpltCallback(hirda);
1360 else
1362 /* Reset Rx transfer counter */
1363 hirda->RxXferCount = 0U;
1365 /* Clear the Error flags in the ICR register */
1366 __HAL_IRDA_CLEAR_FLAG(hirda, IRDA_CLEAR_OREF | IRDA_CLEAR_NEF | IRDA_CLEAR_PEF | IRDA_CLEAR_FEF);
1368 /* Restore hirda->RxState to Ready */
1369 hirda->RxState = HAL_IRDA_STATE_READY;
1371 /* As no DMA to be aborted, call directly user Abort complete callback */
1372 HAL_IRDA_AbortReceiveCpltCallback(hirda);
1375 return HAL_OK;
1379 * @brief Handle IRDA interrupt request.
1380 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
1381 * the configuration information for the specified IRDA module.
1382 * @retval None
1384 void HAL_IRDA_IRQHandler(IRDA_HandleTypeDef *hirda)
1386 uint32_t isrflags = READ_REG(hirda->Instance->ISR);
1387 uint32_t cr1its = READ_REG(hirda->Instance->CR1);
1388 uint32_t cr3its;
1389 uint32_t errorflags;
1391 /* If no error occurs */
1392 errorflags = (isrflags & (uint32_t)(USART_ISR_PE | USART_ISR_FE | USART_ISR_ORE | USART_ISR_NE));
1393 if (errorflags == RESET)
1395 /* IRDA in mode Receiver ---------------------------------------------------*/
1396 if(((isrflags & USART_ISR_RXNE) != RESET) && ((cr1its & USART_CR1_RXNEIE) != RESET))
1398 IRDA_Receive_IT(hirda);
1399 return;
1403 /* If some errors occur */
1404 cr3its = READ_REG(hirda->Instance->CR3);
1405 if( (errorflags != RESET)
1406 && ( ((cr3its & USART_CR3_EIE) != RESET)
1407 || ((cr1its & (USART_CR1_RXNEIE | USART_CR1_PEIE)) != RESET)) )
1409 /* IRDA parity error interrupt occurred -------------------------------------*/
1410 if(((isrflags & USART_ISR_PE) != RESET) && ((cr1its & USART_CR1_PEIE) != RESET))
1412 __HAL_IRDA_CLEAR_IT(hirda, IRDA_CLEAR_PEF);
1414 hirda->ErrorCode |= HAL_IRDA_ERROR_PE;
1417 /* IRDA frame error interrupt occurred --------------------------------------*/
1418 if(((isrflags & USART_ISR_FE) != RESET) && ((cr3its & USART_CR3_EIE) != RESET))
1420 __HAL_IRDA_CLEAR_IT(hirda, IRDA_CLEAR_FEF);
1422 hirda->ErrorCode |= HAL_IRDA_ERROR_FE;
1425 /* IRDA noise error interrupt occurred --------------------------------------*/
1426 if(((isrflags & USART_ISR_NE) != RESET) && ((cr3its & USART_CR3_EIE) != RESET))
1428 __HAL_IRDA_CLEAR_IT(hirda, IRDA_CLEAR_NEF);
1430 hirda->ErrorCode |= HAL_IRDA_ERROR_NE;
1433 /* IRDA Over-Run interrupt occurred -----------------------------------------*/
1434 if(((isrflags & USART_ISR_ORE) != RESET) &&
1435 (((cr1its & USART_CR1_RXNEIE) != RESET) || ((cr3its & USART_CR3_EIE) != RESET)))
1437 __HAL_IRDA_CLEAR_IT(hirda, IRDA_CLEAR_OREF);
1439 hirda->ErrorCode |= HAL_IRDA_ERROR_ORE;
1442 /* Call IRDA Error Call back function if need be --------------------------*/
1443 if(hirda->ErrorCode != HAL_IRDA_ERROR_NONE)
1445 /* IRDA in mode Receiver ---------------------------------------------------*/
1446 if(((isrflags & USART_ISR_RXNE) != RESET) && ((cr1its & USART_CR1_RXNEIE) != RESET))
1448 IRDA_Receive_IT(hirda);
1451 /* If Overrun error occurs, or if any error occurs in DMA mode reception,
1452 consider error as blocking */
1453 if (((hirda->ErrorCode & HAL_IRDA_ERROR_ORE) != RESET) ||
1454 (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAR)))
1456 /* Blocking error : transfer is aborted
1457 Set the IRDA state ready to be able to start again the process,
1458 Disable Rx Interrupts, and disable Rx DMA request, if ongoing */
1459 IRDA_EndRxTransfer(hirda);
1461 /* Disable the IRDA DMA Rx request if enabled */
1462 if (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAR))
1464 CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAR);
1466 /* Abort the IRDA DMA Rx channel */
1467 if(hirda->hdmarx != NULL)
1469 /* Set the IRDA DMA Abort callback :
1470 will lead to call HAL_IRDA_ErrorCallback() at end of DMA abort procedure */
1471 hirda->hdmarx->XferAbortCallback = IRDA_DMAAbortOnError;
1473 /* Abort DMA RX */
1474 if(HAL_DMA_Abort_IT(hirda->hdmarx) != HAL_OK)
1476 /* Call Directly hirda->hdmarx->XferAbortCallback function in case of error */
1477 hirda->hdmarx->XferAbortCallback(hirda->hdmarx);
1480 else
1482 /* Call user error callback */
1483 HAL_IRDA_ErrorCallback(hirda);
1486 else
1488 /* Call user error callback */
1489 HAL_IRDA_ErrorCallback(hirda);
1492 else
1494 /* Non Blocking error : transfer could go on.
1495 Error is notified to user through user error callback */
1496 HAL_IRDA_ErrorCallback(hirda);
1497 hirda->ErrorCode = HAL_IRDA_ERROR_NONE;
1500 return;
1502 } /* End if some error occurs */
1504 /* IRDA in mode Transmitter ------------------------------------------------*/
1505 if(((isrflags & USART_ISR_TXE) != RESET) && ((cr1its & USART_CR1_TXEIE) != RESET))
1507 IRDA_Transmit_IT(hirda);
1508 return;
1511 /* IRDA in mode Transmitter (transmission end) -----------------------------*/
1512 if(((isrflags & USART_ISR_TC) != RESET) && ((cr1its & USART_CR1_TCIE) != RESET))
1514 IRDA_EndTransmit_IT(hirda);
1515 return;
1521 * @brief Tx Transfer completed callback.
1522 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
1523 * the configuration information for the specified IRDA module.
1524 * @retval None
1526 __weak void HAL_IRDA_TxCpltCallback(IRDA_HandleTypeDef *hirda)
1528 /* Prevent unused argument(s) compilation warning */
1529 UNUSED(hirda);
1531 /* NOTE : This function should not be modified, when the callback is needed,
1532 the HAL_IRDA_TxCpltCallback can be implemented in the user file.
1537 * @brief Tx Half Transfer completed callback.
1538 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
1539 * the configuration information for the specified USART module.
1540 * @retval None
1542 __weak void HAL_IRDA_TxHalfCpltCallback(IRDA_HandleTypeDef *hirda)
1544 /* Prevent unused argument(s) compilation warning */
1545 UNUSED(hirda);
1547 /* NOTE : This function should not be modified, when the callback is needed,
1548 the HAL_IRDA_TxHalfCpltCallback can be implemented in the user file.
1553 * @brief Rx Transfer completed callback.
1554 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
1555 * the configuration information for the specified IRDA module.
1556 * @retval None
1558 __weak void HAL_IRDA_RxCpltCallback(IRDA_HandleTypeDef *hirda)
1560 /* Prevent unused argument(s) compilation warning */
1561 UNUSED(hirda);
1563 /* NOTE : This function should not be modified, when the callback is needed,
1564 the HAL_IRDA_RxCpltCallback can be implemented in the user file.
1569 * @brief Rx Half Transfer complete callback.
1570 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
1571 * the configuration information for the specified IRDA module.
1572 * @retval None
1574 __weak void HAL_IRDA_RxHalfCpltCallback(IRDA_HandleTypeDef *hirda)
1576 /* Prevent unused argument(s) compilation warning */
1577 UNUSED(hirda);
1579 /* NOTE : This function should not be modified, when the callback is needed,
1580 the HAL_IRDA_RxHalfCpltCallback can be implemented in the user file.
1585 * @brief IRDA error callback.
1586 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
1587 * the configuration information for the specified IRDA module.
1588 * @retval None
1590 __weak void HAL_IRDA_ErrorCallback(IRDA_HandleTypeDef *hirda)
1592 /* Prevent unused argument(s) compilation warning */
1593 UNUSED(hirda);
1595 /* NOTE : This function should not be modified, when the callback is needed,
1596 the HAL_IRDA_ErrorCallback can be implemented in the user file.
1601 * @brief IRDA Abort Complete callback.
1602 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
1603 * the configuration information for the specified IRDA module.
1604 * @retval None
1606 __weak void HAL_IRDA_AbortCpltCallback (IRDA_HandleTypeDef *hirda)
1608 /* Prevent unused argument(s) compilation warning */
1609 UNUSED(hirda);
1611 /* NOTE : This function should not be modified, when the callback is needed,
1612 the HAL_IRDA_AbortCpltCallback can be implemented in the user file.
1617 * @brief IRDA Abort Complete callback.
1618 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
1619 * the configuration information for the specified IRDA module.
1620 * @retval None
1622 __weak void HAL_IRDA_AbortTransmitCpltCallback (IRDA_HandleTypeDef *hirda)
1624 /* Prevent unused argument(s) compilation warning */
1625 UNUSED(hirda);
1627 /* NOTE : This function should not be modified, when the callback is needed,
1628 the HAL_IRDA_AbortTransmitCpltCallback can be implemented in the user file.
1633 * @brief IRDA Abort Receive Complete callback.
1634 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
1635 * the configuration information for the specified IRDA module.
1636 * @retval None
1638 __weak void HAL_IRDA_AbortReceiveCpltCallback (IRDA_HandleTypeDef *hirda)
1640 /* Prevent unused argument(s) compilation warning */
1641 UNUSED(hirda);
1643 /* NOTE : This function should not be modified, when the callback is needed,
1644 the HAL_IRDA_AbortReceiveCpltCallback can be implemented in the user file.
1649 * @}
1652 /** @defgroup IRDA_Exported_Functions_Group3 Peripheral State and Error functions
1653 * @brief IRDA State and Errors functions
1655 @verbatim
1656 ==============================================================================
1657 ##### Peripheral State and Error functions #####
1658 ==============================================================================
1659 [..]
1660 This subsection provides a set of functions allowing to return the State of IrDA
1661 communication process and also return Peripheral Errors occurred during communication process
1662 (+) HAL_IRDA_GetState() API can be helpful to check in run-time the state
1663 of the IRDA peripheral handle.
1664 (+) HAL_IRDA_GetError() checks in run-time errors that could occur during
1665 communication.
1667 @endverbatim
1668 * @{
1672 * @brief Return the IRDA handle state.
1673 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
1674 * the configuration information for the specified IRDA module.
1675 * @retval HAL state
1677 HAL_IRDA_StateTypeDef HAL_IRDA_GetState(IRDA_HandleTypeDef *hirda)
1679 /* Return IRDA handle state */
1680 uint32_t temp1= 0x00U, temp2 = 0x00U;
1681 temp1 = hirda->gState;
1682 temp2 = hirda->RxState;
1684 return (HAL_IRDA_StateTypeDef)(temp1 | temp2);
1688 * @brief Return the IRDA handle error code.
1689 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
1690 * the configuration information for the specified IRDA module.
1691 * @retval IRDA Error Code
1693 uint32_t HAL_IRDA_GetError(IRDA_HandleTypeDef *hirda)
1695 return hirda->ErrorCode;
1699 * @}
1703 * @}
1706 /** @defgroup IRDA_Private_Functions IRDA Private Functions
1707 * @{
1711 * @brief Configure the IRDA peripheral.
1712 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
1713 * the configuration information for the specified IRDA module.
1714 * @retval HAL status
1716 static HAL_StatusTypeDef IRDA_SetConfig(IRDA_HandleTypeDef *hirda)
1718 uint32_t tmpreg = 0x00000000U;
1719 IRDA_ClockSourceTypeDef clocksource = IRDA_CLOCKSOURCE_UNDEFINED;
1720 HAL_StatusTypeDef ret = HAL_OK;
1722 /* Check the communication parameters */
1723 assert_param(IS_IRDA_BAUDRATE(hirda->Init.BaudRate));
1724 assert_param(IS_IRDA_WORD_LENGTH(hirda->Init.WordLength));
1725 assert_param(IS_IRDA_PARITY(hirda->Init.Parity));
1726 assert_param(IS_IRDA_TX_RX_MODE(hirda->Init.Mode));
1727 assert_param(IS_IRDA_PRESCALER(hirda->Init.Prescaler));
1728 assert_param(IS_IRDA_POWERMODE(hirda->Init.PowerMode));
1730 /*-------------------------- USART CR1 Configuration -----------------------*/
1731 /* Configure the IRDA Word Length, Parity and transfer Mode:
1732 Set the M bits according to hirda->Init.WordLength value
1733 Set PCE and PS bits according to hirda->Init.Parity value
1734 Set TE and RE bits according to hirda->Init.Mode value */
1735 tmpreg = (uint32_t)hirda->Init.WordLength | hirda->Init.Parity | hirda->Init.Mode ;
1737 MODIFY_REG(hirda->Instance->CR1, IRDA_CR1_FIELDS, tmpreg);
1739 /*-------------------------- USART CR3 Configuration -----------------------*/
1740 MODIFY_REG(hirda->Instance->CR3, USART_CR3_IRLP, hirda->Init.PowerMode);
1742 /*-------------------------- USART GTPR Configuration ----------------------*/
1743 MODIFY_REG(hirda->Instance->GTPR, USART_GTPR_PSC, hirda->Init.Prescaler);
1745 /*-------------------------- USART BRR Configuration -----------------------*/
1746 IRDA_GETCLOCKSOURCE(hirda, clocksource);
1747 switch (clocksource)
1749 case IRDA_CLOCKSOURCE_PCLK1:
1750 hirda->Instance->BRR = (uint16_t)((HAL_RCC_GetPCLK1Freq() + (hirda->Init.BaudRate/2U)) / hirda->Init.BaudRate);
1751 break;
1752 case IRDA_CLOCKSOURCE_PCLK2:
1753 hirda->Instance->BRR = (uint16_t)((HAL_RCC_GetPCLK2Freq() + (hirda->Init.BaudRate/2U)) / hirda->Init.BaudRate);
1754 break;
1755 case IRDA_CLOCKSOURCE_HSI:
1756 hirda->Instance->BRR = (uint16_t)((HSI_VALUE + (hirda->Init.BaudRate/2U)) / hirda->Init.BaudRate);
1757 break;
1758 case IRDA_CLOCKSOURCE_SYSCLK:
1759 hirda->Instance->BRR = (uint16_t)((HAL_RCC_GetSysClockFreq() + (hirda->Init.BaudRate/2U)) / hirda->Init.BaudRate);
1760 break;
1761 case IRDA_CLOCKSOURCE_LSE:
1762 hirda->Instance->BRR = (uint16_t)((LSE_VALUE + (hirda->Init.BaudRate/2U)) / hirda->Init.BaudRate);
1763 break;
1764 case IRDA_CLOCKSOURCE_UNDEFINED:
1765 default:
1766 ret = HAL_ERROR;
1767 break;
1770 return ret;
1774 * @brief Check the IRDA Idle State.
1775 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
1776 * the configuration information for the specified IRDA module.
1777 * @retval HAL status
1779 static HAL_StatusTypeDef IRDA_CheckIdleState(IRDA_HandleTypeDef *hirda)
1781 uint32_t tickstart = 0U;
1783 /* Initialize the IRDA ErrorCode */
1784 hirda->ErrorCode = HAL_IRDA_ERROR_NONE;
1786 /* Init tickstart for timeout managment*/
1787 tickstart = HAL_GetTick();
1789 /* TEACK bits in ISR is checked only when available.
1790 Bit is defined and available only for UART instances supporting WakeUp from Stop Mode feature.
1792 if (IS_UART_WAKEUP_FROMSTOP_INSTANCE(hirda->Instance))
1794 /* Check if the Transmitter is enabled */
1795 if((hirda->Instance->CR1 & USART_CR1_TE) == USART_CR1_TE)
1797 /* Wait until TEACK flag is set */
1798 if(IRDA_WaitOnFlagUntilTimeout(hirda, USART_ISR_TEACK, RESET, tickstart, IRDA_TEACK_REACK_TIMEOUT) != HAL_OK)
1800 /* Timeout occurred */
1801 return HAL_TIMEOUT;
1806 /* Check if the Receiver is enabled */
1807 if((hirda->Instance->CR1 & USART_CR1_RE) == USART_CR1_RE)
1809 /* Wait until REACK flag is set */
1810 if(IRDA_WaitOnFlagUntilTimeout(hirda, USART_ISR_REACK, RESET, tickstart, IRDA_TEACK_REACK_TIMEOUT) != HAL_OK)
1812 /* Timeout Occured */
1813 return HAL_TIMEOUT;
1817 /* Initialize the IRDA state*/
1818 hirda->gState = HAL_IRDA_STATE_READY;
1819 hirda->RxState = HAL_IRDA_STATE_READY;
1821 /* Process Unlocked */
1822 __HAL_UNLOCK(hirda);
1824 return HAL_OK;
1828 * @brief Handle IRDA Communication Timeout.
1829 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
1830 * the configuration information for the specified IRDA module.
1831 * @param Flag Specifies the IRDA flag to check.
1832 * @param Status the new flag status (SET or RESET). The function is locked in a while loop as long as the flag remains set to Status.
1833 * @param Tickstart Tick start value
1834 * @param Timeout Timeout duration
1835 * @retval HAL status
1837 static HAL_StatusTypeDef IRDA_WaitOnFlagUntilTimeout(IRDA_HandleTypeDef *hirda, uint32_t Flag, FlagStatus Status, uint32_t Tickstart, uint32_t Timeout)
1839 /* Wait until flag is set */
1840 while((__HAL_IRDA_GET_FLAG(hirda, Flag) ? SET : RESET) == Status)
1842 /* Check for the Timeout */
1843 if(Timeout != HAL_MAX_DELAY)
1845 if((Timeout == 0U) || ((HAL_GetTick()-Tickstart) > Timeout))
1847 /* Disable TXE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts for the interrupt process */
1848 CLEAR_BIT(hirda->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE));
1849 CLEAR_BIT(hirda->Instance->CR3, USART_CR3_EIE);
1851 hirda->gState = HAL_IRDA_STATE_READY;
1852 hirda->RxState = HAL_IRDA_STATE_READY;
1854 /* Process Unlocked */
1855 __HAL_UNLOCK(hirda);
1857 return HAL_TIMEOUT;
1861 return HAL_OK;
1866 * @brief End ongoing Tx transfer on IRDA peripheral (following error detection or Transmit completion).
1867 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
1868 * the configuration information for the specified IRDA module.
1869 * @retval None
1871 static void IRDA_EndTxTransfer(IRDA_HandleTypeDef *hirda)
1873 /* Disable TXEIE and TCIE interrupts */
1874 CLEAR_BIT(hirda->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE));
1876 /* At end of Tx process, restore hirda->gState to Ready */
1877 hirda->gState = HAL_IRDA_STATE_READY;
1882 * @brief End ongoing Rx transfer on UART peripheral (following error detection or Reception completion).
1883 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
1884 * the configuration information for the specified IRDA module.
1885 * @retval None
1887 static void IRDA_EndRxTransfer(IRDA_HandleTypeDef *hirda)
1889 /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */
1890 CLEAR_BIT(hirda->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE));
1891 CLEAR_BIT(hirda->Instance->CR3, USART_CR3_EIE);
1893 /* At end of Rx process, restore hirda->RxState to Ready */
1894 hirda->RxState = HAL_IRDA_STATE_READY;
1899 * @brief DMA IRDA transmit process complete callback.
1900 * @param hdma Pointer to a DMA_HandleTypeDef structure that contains
1901 * the configuration information for the specified DMA module.
1902 * @retval None
1904 static void IRDA_DMATransmitCplt(DMA_HandleTypeDef *hdma)
1906 IRDA_HandleTypeDef* hirda = (IRDA_HandleTypeDef*)(hdma->Parent);
1908 /* DMA Normal mode */
1909 if ( HAL_IS_BIT_CLR(hdma->Instance->CCR, DMA_CCR_CIRC) )
1911 hirda->TxXferCount = 0U;
1913 /* Disable the DMA transfer for transmit request by resetting the DMAT bit
1914 in the IRDA CR3 register */
1915 CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAT);
1917 /* Enable the IRDA Transmit Complete Interrupt */
1918 SET_BIT(hirda->Instance->CR1, USART_CR1_TCIE);
1920 /* DMA Circular mode */
1921 else
1923 HAL_IRDA_TxCpltCallback(hirda);
1929 * @brief DMA IRDA transmit process half complete callback.
1930 * @param hdma Pointer to a DMA_HandleTypeDef structure that contains
1931 * the configuration information for the specified DMA module.
1932 * @retval None
1934 static void IRDA_DMATransmitHalfCplt(DMA_HandleTypeDef *hdma)
1936 IRDA_HandleTypeDef* hirda = (IRDA_HandleTypeDef*)(hdma->Parent);
1938 HAL_IRDA_TxHalfCpltCallback(hirda);
1942 * @brief DMA IRDA receive process complete callback.
1943 * @param hdma Pointer to a DMA_HandleTypeDef structure that contains
1944 * the configuration information for the specified DMA module.
1945 * @retval None
1947 static void IRDA_DMAReceiveCplt(DMA_HandleTypeDef *hdma)
1949 IRDA_HandleTypeDef* hirda = (IRDA_HandleTypeDef*)(hdma->Parent);
1951 /* DMA Normal mode */
1952 if ( HAL_IS_BIT_CLR(hdma->Instance->CCR, DMA_CCR_CIRC) )
1954 hirda->RxXferCount = 0U;
1956 /* Disable PE and ERR (Frame error, noise error, overrun error) interrupts */
1957 CLEAR_BIT(hirda->Instance->CR1, USART_CR1_PEIE);
1958 CLEAR_BIT(hirda->Instance->CR3, USART_CR3_EIE);
1960 /* Disable the DMA transfer for the receiver request by resetting the DMAR bit
1961 in the IRDA CR3 register */
1962 CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAR);
1964 /* At end of Rx process, restore hirda->RxState to Ready */
1965 hirda->RxState = HAL_IRDA_STATE_READY;
1968 HAL_IRDA_RxCpltCallback(hirda);
1972 * @brief DMA IRDA receive process half complete callback.
1973 * @param hdma Pointer to a DMA_HandleTypeDef structure that contains
1974 * the configuration information for the specified DMA module.
1975 * @retval None
1977 static void IRDA_DMAReceiveHalfCplt(DMA_HandleTypeDef *hdma)
1979 IRDA_HandleTypeDef* hirda = (IRDA_HandleTypeDef*)(hdma->Parent);
1981 HAL_IRDA_RxHalfCpltCallback(hirda);
1985 * @brief DMA IRDA communication error callback.
1986 * @param hdma Pointer to a DMA_HandleTypeDef structure that contains
1987 * the configuration information for the specified DMA module.
1988 * @retval None
1990 static void IRDA_DMAError(DMA_HandleTypeDef *hdma)
1992 IRDA_HandleTypeDef* hirda = (IRDA_HandleTypeDef*)(hdma->Parent);
1994 /* Stop IRDA DMA Tx request if ongoing */
1995 if ( (hirda->gState == HAL_IRDA_STATE_BUSY_TX)
1996 &&(HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAT)) )
1998 hirda->TxXferCount = 0U;
1999 IRDA_EndTxTransfer(hirda);
2002 /* Stop IRDA DMA Rx request if ongoing */
2003 if ( (hirda->RxState == HAL_IRDA_STATE_BUSY_RX)
2004 &&(HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAR)) )
2006 hirda->RxXferCount = 0U;
2007 IRDA_EndRxTransfer(hirda);
2010 hirda->ErrorCode |= HAL_IRDA_ERROR_DMA;
2011 HAL_IRDA_ErrorCallback(hirda);
2015 * @brief DMA IRDA communication abort callback, when initiated by HAL services on Error
2016 * (To be called at end of DMA Abort procedure following error occurrence).
2017 * @param hdma DMA handle.
2018 * @retval None
2020 static void IRDA_DMAAbortOnError(DMA_HandleTypeDef *hdma)
2022 IRDA_HandleTypeDef* hirda = (IRDA_HandleTypeDef*)(hdma->Parent);
2023 hirda->RxXferCount = 0U;
2024 hirda->TxXferCount = 0U;
2026 HAL_IRDA_ErrorCallback(hirda);
2030 * @brief DMA IRDA Tx communication abort callback, when initiated by user
2031 * (To be called at end of DMA Tx Abort procedure following user abort request).
2032 * @note When this callback is executed, User Abort complete call back is called only if no
2033 * Abort still ongoing for Rx DMA Handle.
2034 * @param hdma DMA handle.
2035 * @retval None
2037 static void IRDA_DMATxAbortCallback(DMA_HandleTypeDef *hdma)
2039 IRDA_HandleTypeDef* hirda = (IRDA_HandleTypeDef* )(hdma->Parent);
2041 hirda->hdmatx->XferAbortCallback = NULL;
2043 /* Check if an Abort process is still ongoing */
2044 if(hirda->hdmarx != NULL)
2046 if(hirda->hdmarx->XferAbortCallback != NULL)
2048 return;
2052 /* No Abort process still ongoing : All DMA channels are aborted, call user Abort Complete callback */
2053 hirda->TxXferCount = 0U;
2054 hirda->RxXferCount = 0U;
2056 /* Reset errorCode */
2057 hirda->ErrorCode = HAL_IRDA_ERROR_NONE;
2059 /* Clear the Error flags in the ICR register */
2060 __HAL_IRDA_CLEAR_FLAG(hirda, IRDA_CLEAR_OREF | IRDA_CLEAR_NEF | IRDA_CLEAR_PEF | IRDA_CLEAR_FEF);
2062 /* Restore hirda->gState and hirda->RxState to Ready */
2063 hirda->gState = HAL_IRDA_STATE_READY;
2064 hirda->RxState = HAL_IRDA_STATE_READY;
2066 /* Call user Abort complete callback */
2067 HAL_IRDA_AbortCpltCallback(hirda);
2072 * @brief DMA IRDA Rx communication abort callback, when initiated by user
2073 * (To be called at end of DMA Rx Abort procedure following user abort request).
2074 * @note When this callback is executed, User Abort complete call back is called only if no
2075 * Abort still ongoing for Tx DMA Handle.
2076 * @param hdma DMA handle.
2077 * @retval None
2079 static void IRDA_DMARxAbortCallback(DMA_HandleTypeDef *hdma)
2081 IRDA_HandleTypeDef* hirda = (IRDA_HandleTypeDef* )(hdma->Parent);
2083 hirda->hdmarx->XferAbortCallback = NULL;
2085 /* Check if an Abort process is still ongoing */
2086 if(hirda->hdmatx != NULL)
2088 if(hirda->hdmatx->XferAbortCallback != NULL)
2090 return;
2094 /* No Abort process still ongoing : All DMA channels are aborted, call user Abort Complete callback */
2095 hirda->TxXferCount = 0U;
2096 hirda->RxXferCount = 0U;
2098 /* Reset errorCode */
2099 hirda->ErrorCode = HAL_IRDA_ERROR_NONE;
2101 /* Clear the Error flags in the ICR register */
2102 __HAL_IRDA_CLEAR_FLAG(hirda, IRDA_CLEAR_OREF | IRDA_CLEAR_NEF | IRDA_CLEAR_PEF | IRDA_CLEAR_FEF);
2104 /* Restore hirda->gState and hirda->RxState to Ready */
2105 hirda->gState = HAL_IRDA_STATE_READY;
2106 hirda->RxState = HAL_IRDA_STATE_READY;
2108 /* Call user Abort complete callback */
2109 HAL_IRDA_AbortCpltCallback(hirda);
2114 * @brief DMA IRDA Tx communication abort callback, when initiated by user by a call to
2115 * HAL_IRDA_AbortTransmit_IT API (Abort only Tx transfer)
2116 * (This callback is executed at end of DMA Tx Abort procedure following user abort request,
2117 * and leads to user Tx Abort Complete callback execution).
2118 * @param hdma DMA handle.
2119 * @retval None
2121 static void IRDA_DMATxOnlyAbortCallback(DMA_HandleTypeDef *hdma)
2123 IRDA_HandleTypeDef* hirda = (IRDA_HandleTypeDef*)(hdma->Parent);
2125 hirda->TxXferCount = 0U;
2127 /* Restore hirda->gState to Ready */
2128 hirda->gState = HAL_IRDA_STATE_READY;
2130 /* Call user Abort complete callback */
2131 HAL_IRDA_AbortTransmitCpltCallback(hirda);
2135 * @brief DMA IRDA Rx communication abort callback, when initiated by user by a call to
2136 * HAL_IRDA_AbortReceive_IT API (Abort only Rx transfer)
2137 * (This callback is executed at end of DMA Rx Abort procedure following user abort request,
2138 * and leads to user Rx Abort Complete callback execution).
2139 * @param hdma DMA handle.
2140 * @retval None
2142 static void IRDA_DMARxOnlyAbortCallback(DMA_HandleTypeDef *hdma)
2144 IRDA_HandleTypeDef* hirda = ( IRDA_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent;
2146 hirda->RxXferCount = 0U;
2148 /* Clear the Error flags in the ICR register */
2149 __HAL_IRDA_CLEAR_FLAG(hirda, IRDA_CLEAR_OREF | IRDA_CLEAR_NEF | IRDA_CLEAR_PEF | IRDA_CLEAR_FEF);
2151 /* Restore hirda->RxState to Ready */
2152 hirda->RxState = HAL_IRDA_STATE_READY;
2154 /* Call user Abort complete callback */
2155 HAL_IRDA_AbortReceiveCpltCallback(hirda);
2159 * @brief Send an amount of data in interrupt mode.
2160 * @note Function is called under interruption only, once
2161 * interruptions have been enabled by HAL_IRDA_Transmit_IT().
2162 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
2163 * the configuration information for the specified IRDA module.
2164 * @retval HAL status
2166 static HAL_StatusTypeDef IRDA_Transmit_IT(IRDA_HandleTypeDef *hirda)
2168 uint16_t* tmp;
2170 /* Check that a Tx process is ongoing */
2171 if(hirda->gState == HAL_IRDA_STATE_BUSY_TX)
2173 if(hirda->TxXferCount == 0U)
2175 /* Disable the IRDA Transmit Data Register Empty Interrupt */
2176 CLEAR_BIT(hirda->Instance->CR1, USART_CR1_TXEIE);
2178 /* Enable the IRDA Transmit Complete Interrupt */
2179 SET_BIT(hirda->Instance->CR1, USART_CR1_TCIE);
2181 return HAL_OK;
2183 else
2185 if ((hirda->Init.WordLength == IRDA_WORDLENGTH_9B) && (hirda->Init.Parity == IRDA_PARITY_NONE))
2187 tmp = (uint16_t*) hirda->pTxBuffPtr;
2188 hirda->Instance->TDR = (*tmp & (uint16_t)0x01FFU);
2189 hirda->pTxBuffPtr += 2U;
2191 else
2193 hirda->Instance->TDR = (uint8_t)(*hirda->pTxBuffPtr++ & (uint8_t)0xFFU);
2195 hirda->TxXferCount--;
2197 return HAL_OK;
2200 else
2202 return HAL_BUSY;
2207 * @brief Wrap up transmission in non-blocking mode.
2208 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
2209 * the configuration information for the specified IRDA module.
2210 * @retval HAL status
2212 static HAL_StatusTypeDef IRDA_EndTransmit_IT(IRDA_HandleTypeDef *hirda)
2214 /* Disable the IRDA Transmit Complete Interrupt */
2215 CLEAR_BIT(hirda->Instance->CR1, USART_CR1_TCIE);
2217 /* Tx process is ended, restore hirda->gState to Ready */
2218 hirda->gState = HAL_IRDA_STATE_READY;
2220 HAL_IRDA_TxCpltCallback(hirda);
2222 return HAL_OK;
2226 * @brief Receive an amount of data in interrupt mode.
2227 * @note Function is called under interruption only, once
2228 * interruptions have been enabled by HAL_IRDA_Receive_IT()
2229 * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains
2230 * the configuration information for the specified IRDA module.
2231 * @retval HAL status
2233 static HAL_StatusTypeDef IRDA_Receive_IT(IRDA_HandleTypeDef *hirda)
2235 uint16_t* tmp;
2236 uint16_t uhMask = hirda->Mask;
2237 uint16_t uhdata;
2239 /* Check that a Rx process is ongoing */
2240 if (hirda->RxState == HAL_IRDA_STATE_BUSY_RX)
2242 uhdata = (uint16_t) READ_REG(hirda->Instance->RDR);
2243 if ((hirda->Init.WordLength == IRDA_WORDLENGTH_9B) && (hirda->Init.Parity == IRDA_PARITY_NONE))
2245 tmp = (uint16_t*) hirda->pRxBuffPtr ;
2246 *tmp = (uint16_t)(uhdata & uhMask);
2247 hirda->pRxBuffPtr +=2U;
2249 else
2251 *hirda->pRxBuffPtr++ = (uint8_t)(uhdata & (uint8_t)uhMask);
2254 if(--hirda->RxXferCount == 0U)
2256 /* Disable the IRDA Parity Error Interrupt and RXNE interrupt */
2257 CLEAR_BIT(hirda->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE));
2259 /* Disable the IRDA Error Interrupt: (Frame error, noise error, overrun error) */
2260 CLEAR_BIT(hirda->Instance->CR3, USART_CR3_EIE);
2262 /* Rx process is completed, restore hirda->RxState to Ready */
2263 hirda->RxState = HAL_IRDA_STATE_READY;
2265 HAL_IRDA_RxCpltCallback(hirda);
2267 return HAL_OK;
2270 return HAL_OK;
2272 else
2274 /* Clear RXNE interrupt flag */
2275 __HAL_IRDA_SEND_REQ(hirda, IRDA_RXDATA_FLUSH_REQUEST);
2277 return HAL_BUSY;
2282 * @}
2285 #endif /* HAL_IRDA_MODULE_ENABLED */
2287 * @}
2291 * @}
2294 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/