2 ******************************************************************************
3 * @file stm32f1xx_hal_irda.c
4 * @author MCD Application Team
7 * @brief IRDA HAL module driver.
8 * This file provides firmware functions to manage the following
9 * functionalities of the IrDA SIR ENDEC block (IrDA):
10 * + Initialization and de-initialization functions
11 * + IO operation functions
12 * + Peripheral Control functions
13 * + Peripheral State and Errors functions
15 ==============================================================================
16 ##### How to use this driver #####
17 ==============================================================================
19 The IRDA HAL driver can be used as follows:
21 (#) Declare a IRDA_HandleTypeDef handle structure.
22 (#) Initialize the IRDA low level resources by implementing the HAL_IRDA_MspInit() API:
23 (##) Enable the USARTx interface clock.
24 (##) IRDA pins configuration:
25 (+++) Enable the clock for the IRDA GPIOs.
26 (+++) Configure the IRDA pins as alternate function pull-up.
27 (##) NVIC configuration if you need to use interrupt process (HAL_IRDA_Transmit_IT()
28 and HAL_IRDA_Receive_IT() APIs):
29 (+++) Configure the USARTx interrupt priority.
30 (+++) Enable the NVIC USART IRQ handle.
31 (##) DMA Configuration if you need to use DMA process (HAL_IRDA_Transmit_DMA()
32 and HAL_IRDA_Receive_DMA() APIs):
33 (+++) Declare a DMA handle structure for the Tx/Rx channel.
34 (+++) Enable the DMAx interface clock.
35 (+++) Configure the declared DMA handle structure with the required Tx/Rx parameters.
36 (+++) Configure the DMA Tx/Rx channel.
37 (+++) Associate the initialized DMA handle to the IRDA DMA Tx/Rx handle.
38 (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on the DMA Tx/Rx channel.
39 (+++) Configure the IRDAx interrupt priority and enable the NVIC USART IRQ handle
40 (used for last byte sending completion detection in DMA non circular mode)
42 (#) Program the Baud Rate, Word Length, Parity, IrDA Mode, Prescaler
43 and Mode(Receiver/Transmitter) in the hirda Init structure.
45 (#) Initialize the IRDA registers by calling the HAL_IRDA_Init() API:
46 (++) This API configures also the low level Hardware GPIO, CLOCK, CORTEX...etc)
47 by calling the customized HAL_IRDA_MspInit() API.
49 (@) The specific IRDA interrupts (Transmission complete interrupt,
50 RXNE interrupt and Error Interrupts) will be managed using the macros
51 __HAL_IRDA_ENABLE_IT() and __HAL_IRDA_DISABLE_IT() inside the transmit and receive process.
53 Three operation modes are available within this driver :
55 *** Polling mode IO operation ***
56 =================================
58 (+) Send an amount of data in blocking mode using HAL_IRDA_Transmit()
59 (+) Receive an amount of data in blocking mode using HAL_IRDA_Receive()
61 *** Interrupt mode IO operation ***
62 ===================================
64 (+) Send an amount of data in non blocking mode using HAL_IRDA_Transmit_IT()
65 (+) At transmission end of transfer HAL_IRDA_TxCpltCallback is executed and user can
66 add his own code by customization of function pointer HAL_IRDA_TxCpltCallback
67 (+) Receive an amount of data in non blocking mode using HAL_IRDA_Receive_IT()
68 (+) At reception end of transfer HAL_IRDA_RxCpltCallback is executed and user can
69 add his own code by customization of function pointer HAL_IRDA_RxCpltCallback
70 (+) In case of transfer Error, HAL_IRDA_ErrorCallback() function is executed and user can
71 add his own code by customization of function pointer HAL_IRDA_ErrorCallback
73 *** DMA mode IO operation ***
74 ==============================
76 (+) Send an amount of data in non blocking mode (DMA) using HAL_IRDA_Transmit_DMA()
77 (+) At transmission end of half transfer HAL_IRDA_TxHalfCpltCallback is executed and user can
78 add his own code by customization of function pointer HAL_IRDA_TxHalfCpltCallback
79 (+) At transmission end of transfer HAL_IRDA_TxCpltCallback is executed and user can
80 add his own code by customization of function pointer HAL_IRDA_TxCpltCallback
81 (+) Receive an amount of data in non blocking mode (DMA) using HAL_IRDA_Receive_DMA()
82 (+) At reception end of half transfer HAL_IRDA_RxHalfCpltCallback is executed and user can
83 add his own code by customization of function pointer HAL_IRDA_RxHalfCpltCallback
84 (+) At reception end of transfer HAL_IRDA_RxCpltCallback is executed and user can
85 add his own code by customization of function pointer HAL_IRDA_RxCpltCallback
86 (+) In case of transfer Error, HAL_IRDA_ErrorCallback() function is executed and user can
87 add his own code by customization of function pointer HAL_IRDA_ErrorCallback
88 (+) Pause the DMA Transfer using HAL_IRDA_DMAPause()
89 (+) Resume the DMA Transfer using HAL_IRDA_DMAResume()
90 (+) Stop the DMA Transfer using HAL_IRDA_DMAStop()
92 *** IRDA HAL driver macros list ***
93 ====================================
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 the specified IRDA interrupt has occurred or not
106 (@) You can refer to the IRDA HAL driver header file for more useful macros
109 (@) Additionnal remark: If the parity is enabled, then the MSB bit of the data written
110 in the data register is transmitted but is changed by the parity bit.
111 Depending on the frame length defined by the M bit (8-bits or 9-bits),
112 the possible IRDA frame formats are as listed in the following table:
113 +-------------------------------------------------------------+
114 | M bit | PCE bit | IRDA frame |
115 |---------------------|---------------------------------------|
116 | 0 | 0 | | SB | 8 bit data | 1 STB | |
117 |---------|-----------|---------------------------------------|
118 | 0 | 1 | | SB | 7 bit data | PB | 1 STB | |
119 |---------|-----------|---------------------------------------|
120 | 1 | 0 | | SB | 9 bit data | 1 STB | |
121 |---------|-----------|---------------------------------------|
122 | 1 | 1 | | SB | 8 bit data | PB | 1 STB | |
123 +-------------------------------------------------------------+
124 ******************************************************************************
127 * <h2><center>© COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
129 * Redistribution and use in source and binary forms, with or without modification,
130 * are permitted provided that the following conditions are met:
131 * 1. Redistributions of source code must retain the above copyright notice,
132 * this list of conditions and the following disclaimer.
133 * 2. Redistributions in binary form must reproduce the above copyright notice,
134 * this list of conditions and the following disclaimer in the documentation
135 * and/or other materials provided with the distribution.
136 * 3. Neither the name of STMicroelectronics nor the names of its contributors
137 * may be used to endorse or promote products derived from this software
138 * without specific prior written permission.
140 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
141 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
142 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
143 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
144 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
145 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
146 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
147 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
148 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
149 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
151 ******************************************************************************
154 /* Includes ------------------------------------------------------------------*/
155 #include "stm32f1xx_hal.h"
157 /** @addtogroup STM32F1xx_HAL_Driver
161 /** @defgroup IRDA IRDA
162 * @brief HAL IRDA module driver
165 #ifdef HAL_IRDA_MODULE_ENABLED
167 /* Private typedef -----------------------------------------------------------*/
168 /* Private define ------------------------------------------------------------*/
169 /** @addtogroup IRDA_Private_Constants
175 /* Private macro -------------------------------------------------------------*/
176 /* Private variables ---------------------------------------------------------*/
177 /* Private function prototypes -----------------------------------------------*/
178 /** @addtogroup IRDA_Private_Functions
181 static void IRDA_SetConfig (IRDA_HandleTypeDef
*hirda
);
182 static HAL_StatusTypeDef
IRDA_Transmit_IT(IRDA_HandleTypeDef
*hirda
);
183 static HAL_StatusTypeDef
IRDA_EndTransmit_IT(IRDA_HandleTypeDef
*hirda
);
184 static HAL_StatusTypeDef
IRDA_Receive_IT(IRDA_HandleTypeDef
*hirda
);
185 static void IRDA_DMATransmitCplt(DMA_HandleTypeDef
*hdma
);
186 static void IRDA_DMATransmitHalfCplt(DMA_HandleTypeDef
*hdma
);
187 static void IRDA_DMAReceiveCplt(DMA_HandleTypeDef
*hdma
);
188 static void IRDA_DMAReceiveHalfCplt(DMA_HandleTypeDef
*hdma
);
189 static void IRDA_DMAError(DMA_HandleTypeDef
*hdma
);
190 static void IRDA_DMAAbortOnError(DMA_HandleTypeDef
*hdma
);
191 static void IRDA_DMATxAbortCallback(DMA_HandleTypeDef
*hdma
);
192 static void IRDA_DMARxAbortCallback(DMA_HandleTypeDef
*hdma
);
193 static void IRDA_DMATxOnlyAbortCallback(DMA_HandleTypeDef
*hdma
);
194 static void IRDA_DMARxOnlyAbortCallback(DMA_HandleTypeDef
*hdma
);
195 static HAL_StatusTypeDef
IRDA_WaitOnFlagUntilTimeout(IRDA_HandleTypeDef
*hirda
, uint32_t Flag
, FlagStatus Status
, uint32_t Tickstart
,uint32_t Timeout
);
196 static void IRDA_EndTxTransfer(IRDA_HandleTypeDef
*hirda
);
197 static void IRDA_EndRxTransfer(IRDA_HandleTypeDef
*hirda
);
201 /* Exported functions ---------------------------------------------------------*/
202 /** @defgroup IRDA_Exported_Functions IrDA Exported Functions
206 /** @defgroup IRDA_Exported_Functions_Group1 IrDA Initialization and de-initialization functions
207 * @brief Initialization and Configuration functions
210 ==============================================================================
211 ##### Initialization and Configuration functions #####
212 ==============================================================================
214 This subsection provides a set of functions allowing to initialize the USARTx or the UARTy
216 (+) For the asynchronous mode only these parameters can be configured:
219 (++) Parity: If the parity is enabled, then the MSB bit of the data written
220 in the data register is transmitted but is changed by the parity bit.
221 Depending on the frame length defined by the M bit (8-bits or 9-bits),
222 please refer to Reference manual for possible IRDA frame formats.
223 (++) Prescaler: A pulse of width less than two and greater than one PSC period(s) may or may
224 not be rejected. The receiver set up time should be managed by software. The IrDA physical layer
225 specification specifies a minimum of 10 ms delay between transmission and
226 reception (IrDA is a half duplex protocol).
227 (++) Mode: Receiver/transmitter modes
228 (++) IrDAMode: the IrDA can operate in the Normal mode or in the Low power mode.
230 The HAL_IRDA_Init() API follows IRDA configuration procedures (details for the procedures
231 are available in reference manual).
238 * @brief Initializes the IRDA mode according to the specified
239 * parameters in the IRDA_InitTypeDef and create the associated handle.
240 * @param hirda: Pointer to a IRDA_HandleTypeDef structure that contains
241 * the configuration information for the specified IRDA module.
244 HAL_StatusTypeDef
HAL_IRDA_Init(IRDA_HandleTypeDef
*hirda
)
246 /* Check the IRDA handle allocation */
252 /* Check the parameters */
253 assert_param(IS_IRDA_INSTANCE(hirda
->Instance
));
255 if(hirda
->gState
== HAL_IRDA_STATE_RESET
)
257 /* Allocate lock resource and initialize it */
258 hirda
->Lock
= HAL_UNLOCKED
;
259 /* Init the low level hardware : GPIO, CLOCK, CORTEX...etc */
260 HAL_IRDA_MspInit(hirda
);
263 hirda
->gState
= HAL_IRDA_STATE_BUSY
;
265 /* Disable the IRDA peripheral */
266 __HAL_IRDA_DISABLE(hirda
);
268 /* Set the IRDA communication parameters */
269 IRDA_SetConfig(hirda
);
271 /* In IrDA mode, the following bits must be kept cleared:
272 - LINEN, STOP and CLKEN bits in the USART_CR2 register,
273 - SCEN and HDSEL bits in the USART_CR3 register.*/
274 CLEAR_BIT(hirda
->Instance
->CR2
, (USART_CR2_LINEN
| USART_CR2_STOP
| USART_CR2_CLKEN
));
275 CLEAR_BIT(hirda
->Instance
->CR3
, (USART_CR3_SCEN
| USART_CR3_HDSEL
));
277 /* Enable the IRDA peripheral */
278 __HAL_IRDA_ENABLE(hirda
);
280 /* Set the prescaler */
281 MODIFY_REG(hirda
->Instance
->GTPR
, USART_GTPR_PSC
, hirda
->Init
.Prescaler
);
283 /* Configure the IrDA mode */
284 MODIFY_REG(hirda
->Instance
->CR3
, USART_CR3_IRLP
, hirda
->Init
.IrDAMode
);
286 /* Enable the IrDA mode by setting the IREN bit in the CR3 register */
287 SET_BIT(hirda
->Instance
->CR3
, USART_CR3_IREN
);
289 /* Initialize the IRDA state*/
290 hirda
->ErrorCode
= HAL_IRDA_ERROR_NONE
;
291 hirda
->gState
= HAL_IRDA_STATE_READY
;
292 hirda
->RxState
= HAL_IRDA_STATE_READY
;
298 * @brief DeInitializes the IRDA peripheral
299 * @param hirda: Pointer to a IRDA_HandleTypeDef structure that contains
300 * the configuration information for the specified IRDA module.
303 HAL_StatusTypeDef
HAL_IRDA_DeInit(IRDA_HandleTypeDef
*hirda
)
305 /* Check the IRDA handle allocation */
311 /* Check the parameters */
312 assert_param(IS_IRDA_INSTANCE(hirda
->Instance
));
314 hirda
->gState
= HAL_IRDA_STATE_BUSY
;
316 /* Disable the Peripheral */
317 __HAL_IRDA_DISABLE(hirda
);
319 /* DeInit the low level hardware */
320 HAL_IRDA_MspDeInit(hirda
);
322 hirda
->ErrorCode
= HAL_IRDA_ERROR_NONE
;
323 hirda
->gState
= HAL_IRDA_STATE_RESET
;
324 hirda
->RxState
= HAL_IRDA_STATE_RESET
;
333 * @brief IRDA MSP Init.
334 * @param hirda: Pointer to a IRDA_HandleTypeDef structure that contains
335 * the configuration information for the specified IRDA module.
338 __weak
void HAL_IRDA_MspInit(IRDA_HandleTypeDef
*hirda
)
340 /* Prevent unused argument(s) compilation warning */
342 /* NOTE: This function should not be modified, when the callback is needed,
343 the HAL_IRDA_MspInit can be implemented in the user file
348 * @brief IRDA MSP DeInit.
349 * @param hirda: Pointer to a IRDA_HandleTypeDef structure that contains
350 * the configuration information for the specified IRDA module.
353 __weak
void HAL_IRDA_MspDeInit(IRDA_HandleTypeDef
*hirda
)
355 /* Prevent unused argument(s) compilation warning */
357 /* NOTE: This function should not be modified, when the callback is needed,
358 the HAL_IRDA_MspDeInit can be implemented in the user file
366 /** @defgroup IRDA_Exported_Functions_Group2 IO operation functions
367 * @brief IRDA Transmit and Receive functions
370 ==============================================================================
371 ##### IO operation functions #####
372 ==============================================================================
374 This subsection provides a set of functions allowing to manage the IRDA data transfers.
375 IrDA is a half duplex communication protocol. If the Transmitter is busy, any data
376 on the IrDA receive line will be ignored by the IrDA decoder and if the Receiver
377 is busy, data on the TX from the USART to IrDA will not be encoded by IrDA.
378 While receiving data, transmission should be avoided as the data to be transmitted
381 (#) There are two modes of transfer:
382 (++) Blocking mode: The communication is performed in polling mode.
383 The HAL status of all data processing is returned by the same function
384 after finishing transfer.
385 (++) No-Blocking mode: The communication is performed using Interrupts
386 or DMA, these APIs return the HAL status.
387 The end of the data processing will be indicated through the
388 dedicated IRDA IRQ when using Interrupt mode or the DMA IRQ when
390 The HAL_IRDA_TxCpltCallback(), HAL_IRDA_RxCpltCallback() user callbacks
391 will be executed respectively at the end of the transmit or Receive process
392 The HAL_IRDA_ErrorCallback() user callback will be executed when a communication
395 (#) Blocking mode APIs are:
396 (++) HAL_IRDA_Transmit()
397 (++) HAL_IRDA_Receive()
399 (#) Non Blocking mode APIs with Interrupt are:
400 (++) HAL_IRDA_Transmit_IT()
401 (++) HAL_IRDA_Receive_IT()
402 (++) HAL_IRDA_IRQHandler()
404 (#) Non Blocking mode functions with DMA are:
405 (++) HAL_IRDA_Transmit_DMA()
406 (++) HAL_IRDA_Receive_DMA()
407 (++) HAL_IRDA_DMAPause()
408 (++) HAL_IRDA_DMAResume()
409 (++) HAL_IRDA_DMAStop()
411 (#) A set of Transfer Complete Callbacks are provided in non Blocking mode:
412 (++) HAL_IRDA_TxHalfCpltCallback()
413 (++) HAL_IRDA_TxCpltCallback()
414 (++) HAL_IRDA_RxHalfCpltCallback()
415 (++) HAL_IRDA_RxCpltCallback()
416 (++) HAL_IRDA_ErrorCallback()
423 * @brief Sends an amount of data in blocking mode.
424 * @param hirda: Pointer to a IRDA_HandleTypeDef structure that contains
425 * the configuration information for the specified IRDA module.
426 * @param pData: Pointer to data buffer
427 * @param Size: Amount of data to be sent
428 * @param Timeout: Specify timeout value
431 HAL_StatusTypeDef
HAL_IRDA_Transmit(IRDA_HandleTypeDef
*hirda
, uint8_t *pData
, uint16_t Size
, uint32_t Timeout
)
434 uint32_t tickstart
= 0U;
436 /* Check that a Tx process is not already ongoing */
437 if(hirda
->gState
== HAL_IRDA_STATE_READY
)
439 if((pData
== NULL
) || (Size
== 0U))
447 hirda
->ErrorCode
= HAL_IRDA_ERROR_NONE
;
448 hirda
->gState
= HAL_IRDA_STATE_BUSY_TX
;
450 /* Init tickstart for timeout managment */
451 tickstart
= HAL_GetTick();
453 hirda
->TxXferSize
= Size
;
454 hirda
->TxXferCount
= Size
;
455 while(hirda
->TxXferCount
> 0U)
457 hirda
->TxXferCount
--;
458 if(hirda
->Init
.WordLength
== IRDA_WORDLENGTH_9B
)
460 if(IRDA_WaitOnFlagUntilTimeout(hirda
, IRDA_FLAG_TXE
, RESET
, tickstart
, Timeout
) != HAL_OK
)
464 tmp
= (uint16_t*) pData
;
465 hirda
->Instance
->DR
= (*tmp
& (uint16_t)0x01FF);
466 if(hirda
->Init
.Parity
== IRDA_PARITY_NONE
)
477 if(IRDA_WaitOnFlagUntilTimeout(hirda
, IRDA_FLAG_TXE
, RESET
, tickstart
, Timeout
) != HAL_OK
)
481 hirda
->Instance
->DR
= (*pData
++ & (uint8_t)0xFF);
485 if(IRDA_WaitOnFlagUntilTimeout(hirda
, IRDA_FLAG_TC
, RESET
, tickstart
, Timeout
) != HAL_OK
)
490 /* At end of Tx process, restore hirda->gState to Ready */
491 hirda
->gState
= HAL_IRDA_STATE_READY
;
493 /* Process Unlocked */
505 * @brief Receive an amount of data in blocking mode.
506 * @param hirda: Pointer to a IRDA_HandleTypeDef structure that contains
507 * the configuration information for the specified IRDA module.
508 * @param pData: Pointer to data buffer
509 * @param Size: Amount of data to be received
510 * @param Timeout: Specify timeout value
513 HAL_StatusTypeDef
HAL_IRDA_Receive(IRDA_HandleTypeDef
*hirda
, uint8_t *pData
, uint16_t Size
, uint32_t Timeout
)
516 uint32_t tickstart
= 0U;
518 /* Check that a Rx process is not already ongoing */
519 if(hirda
->RxState
== HAL_IRDA_STATE_READY
)
521 if((pData
== NULL
) || (Size
== 0U))
529 hirda
->ErrorCode
= HAL_IRDA_ERROR_NONE
;
530 hirda
->RxState
= HAL_IRDA_STATE_BUSY_RX
;
532 /* Init tickstart for timeout managment */
533 tickstart
= HAL_GetTick();
535 hirda
->RxXferSize
= Size
;
536 hirda
->RxXferCount
= Size
;
538 /* Check the remain data to be received */
539 while(hirda
->RxXferCount
> 0U)
541 hirda
->RxXferCount
--;
542 if(hirda
->Init
.WordLength
== IRDA_WORDLENGTH_9B
)
544 if(IRDA_WaitOnFlagUntilTimeout(hirda
, IRDA_FLAG_RXNE
, RESET
, tickstart
, Timeout
) != HAL_OK
)
548 tmp
= (uint16_t*)pData
;
549 if(hirda
->Init
.Parity
== IRDA_PARITY_NONE
)
551 *tmp
= (uint16_t)(hirda
->Instance
->DR
& (uint16_t)0x01FF);
556 *tmp
= (uint16_t)(hirda
->Instance
->DR
& (uint16_t)0x00FF);
562 if(IRDA_WaitOnFlagUntilTimeout(hirda
, IRDA_FLAG_RXNE
, RESET
, tickstart
, Timeout
) != HAL_OK
)
566 if(hirda
->Init
.Parity
== IRDA_PARITY_NONE
)
568 *pData
++ = (uint8_t)(hirda
->Instance
->DR
& (uint8_t)0x00FF);
572 *pData
++ = (uint8_t)(hirda
->Instance
->DR
& (uint8_t)0x007F);
577 /* At end of Rx process, restore hirda->RxState to Ready */
578 hirda
->RxState
= HAL_IRDA_STATE_READY
;
580 /* Process Unlocked */
592 * @brief Sends an amount of data in non blocking mode.
593 * @param hirda: Pointer to a IRDA_HandleTypeDef structure that contains
594 * the configuration information for the specified IRDA module.
595 * @param pData: Pointer to data buffer
596 * @param Size: Amount of data to be sent
599 HAL_StatusTypeDef
HAL_IRDA_Transmit_IT(IRDA_HandleTypeDef
*hirda
, uint8_t *pData
, uint16_t Size
)
601 /* Check that a Tx process is not already ongoing */
602 if(hirda
->gState
== HAL_IRDA_STATE_READY
)
604 if((pData
== NULL
) || (Size
== 0U))
611 hirda
->pTxBuffPtr
= pData
;
612 hirda
->TxXferSize
= Size
;
613 hirda
->TxXferCount
= Size
;
615 hirda
->ErrorCode
= HAL_IRDA_ERROR_NONE
;
616 hirda
->gState
= HAL_IRDA_STATE_BUSY_TX
;
618 /* Process Unlocked */
621 /* Enable the IRDA Transmit data register empty Interrupt */
622 __HAL_IRDA_ENABLE_IT(hirda
, IRDA_IT_TXE
);
633 * @brief Receives an amount of data in non blocking mode.
634 * @param hirda: Pointer to a IRDA_HandleTypeDef structure that contains
635 * the configuration information for the specified IRDA module.
636 * @param pData: Pointer to data buffer
637 * @param Size: Amount of data to be received
640 HAL_StatusTypeDef
HAL_IRDA_Receive_IT(IRDA_HandleTypeDef
*hirda
, uint8_t *pData
, uint16_t Size
)
642 /* Check that a Rx process is not already ongoing */
643 if(hirda
->RxState
== HAL_IRDA_STATE_READY
)
645 if((pData
== NULL
) || (Size
== 0U))
653 hirda
->pRxBuffPtr
= pData
;
654 hirda
->RxXferSize
= Size
;
655 hirda
->RxXferCount
= Size
;
657 hirda
->ErrorCode
= HAL_IRDA_ERROR_NONE
;
658 hirda
->RxState
= HAL_IRDA_STATE_BUSY_RX
;
660 /* Process Unlocked */
663 /* Enable the IRDA Parity Error Interrupt */
664 __HAL_IRDA_ENABLE_IT(hirda
, IRDA_IT_PE
);
666 /* Enable the IRDA Error Interrupt: (Frame error, noise error, overrun error) */
667 __HAL_IRDA_ENABLE_IT(hirda
, IRDA_IT_ERR
);
669 /* Enable the IRDA Data Register not empty Interrupt */
670 __HAL_IRDA_ENABLE_IT(hirda
, IRDA_IT_RXNE
);
681 * @brief Sends an amount of data in non blocking mode.
682 * @param hirda: Pointer to a IRDA_HandleTypeDef structure that contains
683 * the configuration information for the specified IRDA module.
684 * @param pData: Pointer to data buffer
685 * @param Size: Amount of data to be sent
688 HAL_StatusTypeDef
HAL_IRDA_Transmit_DMA(IRDA_HandleTypeDef
*hirda
, uint8_t *pData
, uint16_t Size
)
692 /* Check that a Tx process is not already ongoing */
693 if(hirda
->gState
== HAL_IRDA_STATE_READY
)
695 if((pData
== NULL
) || (Size
== 0U))
703 hirda
->pTxBuffPtr
= pData
;
704 hirda
->TxXferSize
= Size
;
705 hirda
->TxXferCount
= Size
;
707 hirda
->ErrorCode
= HAL_IRDA_ERROR_NONE
;
708 hirda
->gState
= HAL_IRDA_STATE_BUSY_TX
;
710 /* Set the IRDA DMA transfer complete callback */
711 hirda
->hdmatx
->XferCpltCallback
= IRDA_DMATransmitCplt
;
713 /* Set the IRDA DMA half transfer complete callback */
714 hirda
->hdmatx
->XferHalfCpltCallback
= IRDA_DMATransmitHalfCplt
;
716 /* Set the DMA error callback */
717 hirda
->hdmatx
->XferErrorCallback
= IRDA_DMAError
;
719 /* Set the DMA abort callback */
720 hirda
->hdmatx
->XferAbortCallback
= NULL
;
722 /* Enable the IRDA transmit DMA Channel */
723 tmp
= (uint32_t*)&pData
;
724 HAL_DMA_Start_IT(hirda
->hdmatx
, *(uint32_t*)tmp
, (uint32_t)&hirda
->Instance
->DR
, Size
);
726 /* Clear the TC flag in the SR register by writing 0 to it */
727 __HAL_IRDA_CLEAR_FLAG(hirda
, IRDA_FLAG_TC
);
729 /* Process Unlocked */
732 /* Enable the DMA transfer for transmit request by setting the DMAT bit
733 in the USART CR3 register */
734 SET_BIT(hirda
->Instance
->CR3
, USART_CR3_DMAT
);
745 * @brief Receives an amount of data in non blocking mode.
746 * @param hirda: Pointer to a IRDA_HandleTypeDef structure that contains
747 * the configuration information for the specified IRDA module.
748 * @param pData: Pointer to data buffer
749 * @param Size: Amount of data to be received
750 * @note When the IRDA parity is enabled (PCE = 1) the data received contain the parity bit.
753 HAL_StatusTypeDef
HAL_IRDA_Receive_DMA(IRDA_HandleTypeDef
*hirda
, uint8_t *pData
, uint16_t Size
)
757 /* Check that a Rx process is not already ongoing */
758 if(hirda
->RxState
== HAL_IRDA_STATE_READY
)
760 if((pData
== NULL
) || (Size
== 0U))
768 hirda
->pRxBuffPtr
= pData
;
769 hirda
->RxXferSize
= Size
;
771 hirda
->ErrorCode
= HAL_IRDA_ERROR_NONE
;
772 hirda
->RxState
= HAL_IRDA_STATE_BUSY_RX
;
774 /* Set the IRDA DMA transfer complete callback */
775 hirda
->hdmarx
->XferCpltCallback
= IRDA_DMAReceiveCplt
;
777 /* Set the IRDA DMA half transfer complete callback */
778 hirda
->hdmarx
->XferHalfCpltCallback
= IRDA_DMAReceiveHalfCplt
;
780 /* Set the DMA error callback */
781 hirda
->hdmarx
->XferErrorCallback
= IRDA_DMAError
;
783 /* Set the DMA abort callback */
784 hirda
->hdmarx
->XferAbortCallback
= NULL
;
786 /* Enable the DMA channel */
787 tmp
= (uint32_t*)&pData
;
788 HAL_DMA_Start_IT(hirda
->hdmarx
, (uint32_t)&hirda
->Instance
->DR
, *(uint32_t*)tmp
, Size
);
790 /* Clear the Overrun flag just before enabling the DMA Rx request: can be mandatory for the second transfer */
791 __HAL_IRDA_CLEAR_OREFLAG(hirda
);
793 /* Process Unlocked */
796 /* Enable the IRDA Parity Error Interrupt */
797 SET_BIT(hirda
->Instance
->CR1
, USART_CR1_PEIE
);
799 /* Enable the IRDA Error Interrupt: (Frame error, noise error, overrun error) */
800 SET_BIT(hirda
->Instance
->CR3
, USART_CR3_EIE
);
802 /* Enable the DMA transfer for the receiver request by setting the DMAR bit
803 in the USART CR3 register */
804 SET_BIT(hirda
->Instance
->CR3
, USART_CR3_DMAR
);
815 * @brief Pauses the DMA Transfer.
816 * @param hirda: Pointer to a IRDA_HandleTypeDef structure that contains
817 * the configuration information for the specified IRDA module.
820 HAL_StatusTypeDef
HAL_IRDA_DMAPause(IRDA_HandleTypeDef
*hirda
)
822 uint32_t dmarequest
= 0x00U
;
827 dmarequest
= HAL_IS_BIT_SET(hirda
->Instance
->CR3
, USART_CR3_DMAT
);
828 if((hirda
->gState
== HAL_IRDA_STATE_BUSY_TX
) && dmarequest
)
830 /* Disable the IRDA DMA Tx request */
831 CLEAR_BIT(hirda
->Instance
->CR3
, USART_CR3_DMAT
);
834 dmarequest
= HAL_IS_BIT_SET(hirda
->Instance
->CR3
, USART_CR3_DMAR
);
835 if((hirda
->RxState
== HAL_IRDA_STATE_BUSY_RX
) && dmarequest
)
837 /* Disable PE and ERR (Frame error, noise error, overrun error) interrupts */
838 CLEAR_BIT(hirda
->Instance
->CR1
, USART_CR1_PEIE
);
839 CLEAR_BIT(hirda
->Instance
->CR3
, USART_CR3_EIE
);
841 /* Disable the IRDA DMA Rx request */
842 CLEAR_BIT(hirda
->Instance
->CR3
, USART_CR3_DMAR
);
845 /* Process Unlocked */
852 * @brief Resumes the DMA Transfer.
853 * @param hirda: Pointer to a IRDA_HandleTypeDef structure that contains
854 * the configuration information for the specified IRDA module.
857 HAL_StatusTypeDef
HAL_IRDA_DMAResume(IRDA_HandleTypeDef
*hirda
)
862 if(hirda
->gState
== HAL_IRDA_STATE_BUSY_TX
)
864 /* Enable the IRDA DMA Tx request */
865 SET_BIT(hirda
->Instance
->CR3
, USART_CR3_DMAT
);
868 if(hirda
->RxState
== HAL_IRDA_STATE_BUSY_RX
)
870 /* Clear the Overrun flag before resuming the Rx transfer */
871 __HAL_IRDA_CLEAR_OREFLAG(hirda
);
873 /* Reenable PE and ERR (Frame error, noise error, overrun error) interrupts */
874 SET_BIT(hirda
->Instance
->CR1
, USART_CR1_PEIE
);
875 SET_BIT(hirda
->Instance
->CR3
, USART_CR3_EIE
);
877 /* Enable the IRDA DMA Rx request */
878 SET_BIT(hirda
->Instance
->CR3
, USART_CR3_DMAR
);
881 /* Process Unlocked */
888 * @brief Stops the DMA Transfer.
889 * @param hirda: Pointer to a IRDA_HandleTypeDef structure that contains
890 * the configuration information for the specified IRDA module.
893 HAL_StatusTypeDef
HAL_IRDA_DMAStop(IRDA_HandleTypeDef
*hirda
)
895 uint32_t dmarequest
= 0x00U
;
896 /* The Lock is not implemented on this API to allow the user application
897 to call the HAL IRDA API under callbacks HAL_IRDA_TxCpltCallback() / HAL_IRDA_RxCpltCallback():
898 when calling HAL_DMA_Abort() API the DMA TX/RX Transfer complete interrupt is generated
899 and the correspond call back is executed HAL_IRDA_TxCpltCallback() / HAL_IRDA_RxCpltCallback()
902 /* Stop IRDA DMA Tx request if ongoing */
903 dmarequest
= HAL_IS_BIT_SET(hirda
->Instance
->CR3
, USART_CR3_DMAT
);
904 if((hirda
->gState
== HAL_IRDA_STATE_BUSY_TX
) && dmarequest
)
906 CLEAR_BIT(hirda
->Instance
->CR3
, USART_CR3_DMAT
);
908 /* Abort the IRDA DMA Tx channel */
909 if(hirda
->hdmatx
!= NULL
)
911 HAL_DMA_Abort(hirda
->hdmatx
);
913 IRDA_EndTxTransfer(hirda
);
916 /* Stop IRDA DMA Rx request if ongoing */
917 dmarequest
= HAL_IS_BIT_SET(hirda
->Instance
->CR3
, USART_CR3_DMAR
);
918 if((hirda
->RxState
== HAL_IRDA_STATE_BUSY_RX
) && dmarequest
)
920 CLEAR_BIT(hirda
->Instance
->CR3
, USART_CR3_DMAR
);
922 /* Abort the IRDA DMA Rx channel */
923 if(hirda
->hdmarx
!= NULL
)
925 HAL_DMA_Abort(hirda
->hdmarx
);
927 IRDA_EndRxTransfer(hirda
);
934 * @brief Abort ongoing transfers (blocking mode).
935 * @param hirda IRDA handle.
936 * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode.
937 * This procedure performs following operations :
938 * - Disable PPP Interrupts
939 * - Disable the DMA transfer in the peripheral register (if enabled)
940 * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode)
941 * - Set handle State to READY
942 * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed.
945 HAL_StatusTypeDef
HAL_IRDA_Abort(IRDA_HandleTypeDef
*hirda
)
947 /* Disable TXEIE, TCIE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */
948 CLEAR_BIT(hirda
->Instance
->CR1
, (USART_CR1_RXNEIE
| USART_CR1_PEIE
| USART_CR1_TXEIE
| USART_CR1_TCIE
));
949 CLEAR_BIT(hirda
->Instance
->CR3
, USART_CR3_EIE
);
951 /* Disable the IRDA DMA Tx request if enabled */
952 if(HAL_IS_BIT_SET(hirda
->Instance
->CR3
, USART_CR3_DMAT
))
954 CLEAR_BIT(hirda
->Instance
->CR3
, USART_CR3_DMAT
);
956 /* Abort the IRDA DMA Tx channel: use blocking DMA Abort API (no callback) */
957 if(hirda
->hdmatx
!= NULL
)
959 /* Set the IRDA DMA Abort callback to Null.
960 No call back execution at end of DMA abort procedure */
961 hirda
->hdmatx
->XferAbortCallback
= NULL
;
963 HAL_DMA_Abort(hirda
->hdmatx
);
967 /* Disable the IRDA DMA Rx request if enabled */
968 if(HAL_IS_BIT_SET(hirda
->Instance
->CR3
, USART_CR3_DMAR
))
970 CLEAR_BIT(hirda
->Instance
->CR3
, USART_CR3_DMAR
);
972 /* Abort the IRDA DMA Rx channel: use blocking DMA Abort API (no callback) */
973 if(hirda
->hdmarx
!= NULL
)
975 /* Set the IRDA DMA Abort callback to Null.
976 No call back execution at end of DMA abort procedure */
977 hirda
->hdmarx
->XferAbortCallback
= NULL
;
979 HAL_DMA_Abort(hirda
->hdmarx
);
983 /* Reset Tx and Rx transfer counters */
984 hirda
->TxXferCount
= 0x00U
;
985 hirda
->RxXferCount
= 0x00U
;
987 /* Reset ErrorCode */
988 hirda
->ErrorCode
= HAL_IRDA_ERROR_NONE
;
990 /* Restore hirda->RxState and hirda->gState to Ready */
991 hirda
->RxState
= HAL_IRDA_STATE_READY
;
992 hirda
->gState
= HAL_IRDA_STATE_READY
;
998 * @brief Abort ongoing Transmit transfer (blocking mode).
999 * @param hirda IRDA handle.
1000 * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode.
1001 * This procedure performs following operations :
1002 * - Disable PPP Interrupts
1003 * - Disable the DMA transfer in the peripheral register (if enabled)
1004 * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode)
1005 * - Set handle State to READY
1006 * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed.
1007 * @retval HAL status
1009 HAL_StatusTypeDef
HAL_IRDA_AbortTransmit(IRDA_HandleTypeDef
*hirda
)
1011 /* Disable TXEIE and TCIE interrupts */
1012 CLEAR_BIT(hirda
->Instance
->CR1
, (USART_CR1_TXEIE
| USART_CR1_TCIE
));
1014 /* Disable the IRDA DMA Tx request if enabled */
1015 if(HAL_IS_BIT_SET(hirda
->Instance
->CR3
, USART_CR3_DMAT
))
1017 CLEAR_BIT(hirda
->Instance
->CR3
, USART_CR3_DMAT
);
1019 /* Abort the IRDA DMA Tx channel : use blocking DMA Abort API (no callback) */
1020 if(hirda
->hdmatx
!= NULL
)
1022 /* Set the IRDA DMA Abort callback to Null.
1023 No call back execution at end of DMA abort procedure */
1024 hirda
->hdmatx
->XferAbortCallback
= NULL
;
1026 HAL_DMA_Abort(hirda
->hdmatx
);
1030 /* Reset Tx transfer counter */
1031 hirda
->TxXferCount
= 0x00U
;
1033 /* Restore hirda->gState to Ready */
1034 hirda
->gState
= HAL_IRDA_STATE_READY
;
1040 * @brief Abort ongoing Receive transfer (blocking mode).
1041 * @param hirda IRDA handle.
1042 * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode.
1043 * This procedure performs following operations :
1044 * - Disable PPP Interrupts
1045 * - Disable the DMA transfer in the peripheral register (if enabled)
1046 * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode)
1047 * - Set handle State to READY
1048 * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed.
1049 * @retval HAL status
1051 HAL_StatusTypeDef
HAL_IRDA_AbortReceive(IRDA_HandleTypeDef
*hirda
)
1053 /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */
1054 CLEAR_BIT(hirda
->Instance
->CR1
, (USART_CR1_RXNEIE
| USART_CR1_PEIE
));
1055 CLEAR_BIT(hirda
->Instance
->CR3
, USART_CR3_EIE
);
1057 /* Disable the IRDA DMA Rx request if enabled */
1058 if(HAL_IS_BIT_SET(hirda
->Instance
->CR3
, USART_CR3_DMAR
))
1060 CLEAR_BIT(hirda
->Instance
->CR3
, USART_CR3_DMAR
);
1062 /* Abort the IRDA DMA Rx channel : use blocking DMA Abort API (no callback) */
1063 if(hirda
->hdmarx
!= NULL
)
1065 /* Set the IRDA DMA Abort callback to Null.
1066 No call back execution at end of DMA abort procedure */
1067 hirda
->hdmarx
->XferAbortCallback
= NULL
;
1069 HAL_DMA_Abort(hirda
->hdmarx
);
1073 /* Reset Rx transfer counter */
1074 hirda
->RxXferCount
= 0x00U
;
1076 /* Restore hirda->RxState to Ready */
1077 hirda
->RxState
= HAL_IRDA_STATE_READY
;
1083 * @brief Abort ongoing transfers (Interrupt mode).
1084 * @param hirda IRDA handle.
1085 * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode.
1086 * This procedure performs following operations :
1087 * - Disable PPP Interrupts
1088 * - Disable the DMA transfer in the peripheral register (if enabled)
1089 * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode)
1090 * - Set handle State to READY
1091 * - At abort completion, call user abort complete callback
1092 * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be
1093 * considered as completed only when user abort complete callback is executed (not when exiting function).
1094 * @retval HAL status
1096 HAL_StatusTypeDef
HAL_IRDA_Abort_IT(IRDA_HandleTypeDef
*hirda
)
1098 uint32_t AbortCplt
= 0x01U
;
1100 /* Disable TXEIE, TCIE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */
1101 CLEAR_BIT(hirda
->Instance
->CR1
, (USART_CR1_RXNEIE
| USART_CR1_PEIE
| USART_CR1_TXEIE
| USART_CR1_TCIE
));
1102 CLEAR_BIT(hirda
->Instance
->CR3
, USART_CR3_EIE
);
1104 /* If DMA Tx and/or DMA Rx Handles are associated to IRDA Handle, DMA Abort complete callbacks should be initialised
1105 before any call to DMA Abort functions */
1106 /* DMA Tx Handle is valid */
1107 if(hirda
->hdmatx
!= NULL
)
1109 /* Set DMA Abort Complete callback if IRDA DMA Tx request if enabled.
1110 Otherwise, set it to NULL */
1111 if(HAL_IS_BIT_SET(hirda
->Instance
->CR3
, USART_CR3_DMAT
))
1113 hirda
->hdmatx
->XferAbortCallback
= IRDA_DMATxAbortCallback
;
1117 hirda
->hdmatx
->XferAbortCallback
= NULL
;
1120 /* DMA Rx Handle is valid */
1121 if(hirda
->hdmarx
!= NULL
)
1123 /* Set DMA Abort Complete callback if IRDA DMA Rx request if enabled.
1124 Otherwise, set it to NULL */
1125 if(HAL_IS_BIT_SET(hirda
->Instance
->CR3
, USART_CR3_DMAR
))
1127 hirda
->hdmarx
->XferAbortCallback
= IRDA_DMARxAbortCallback
;
1131 hirda
->hdmarx
->XferAbortCallback
= NULL
;
1135 /* Disable the IRDA DMA Tx request if enabled */
1136 if(HAL_IS_BIT_SET(hirda
->Instance
->CR3
, USART_CR3_DMAT
))
1138 /* Disable DMA Tx at IRDA level */
1139 CLEAR_BIT(hirda
->Instance
->CR3
, USART_CR3_DMAT
);
1141 /* Abort the IRDA DMA Tx channel : use non blocking DMA Abort API (callback) */
1142 if(hirda
->hdmatx
!= NULL
)
1144 /* IRDA Tx DMA Abort callback has already been initialised :
1145 will lead to call HAL_IRDA_AbortCpltCallback() at end of DMA abort procedure */
1148 if(HAL_DMA_Abort_IT(hirda
->hdmatx
) != HAL_OK
)
1150 hirda
->hdmatx
->XferAbortCallback
= NULL
;
1159 /* Disable the IRDA DMA Rx request if enabled */
1160 if(HAL_IS_BIT_SET(hirda
->Instance
->CR3
, USART_CR3_DMAR
))
1162 CLEAR_BIT(hirda
->Instance
->CR3
, USART_CR3_DMAR
);
1164 /* Abort the IRDA DMA Rx channel : use non blocking DMA Abort API (callback) */
1165 if(hirda
->hdmarx
!= NULL
)
1167 /* IRDA Rx DMA Abort callback has already been initialised :
1168 will lead to call HAL_IRDA_AbortCpltCallback() at end of DMA abort procedure */
1171 if(HAL_DMA_Abort_IT(hirda
->hdmarx
) != HAL_OK
)
1173 hirda
->hdmarx
->XferAbortCallback
= NULL
;
1183 /* if no DMA abort complete callback execution is required => call user Abort Complete callback */
1184 if(AbortCplt
== 0x01U
)
1186 /* Reset Tx and Rx transfer counters */
1187 hirda
->TxXferCount
= 0x00U
;
1188 hirda
->RxXferCount
= 0x00U
;
1190 /* Reset ErrorCode */
1191 hirda
->ErrorCode
= HAL_IRDA_ERROR_NONE
;
1193 /* Restore hirda->gState and hirda->RxState to Ready */
1194 hirda
->gState
= HAL_IRDA_STATE_READY
;
1195 hirda
->RxState
= HAL_IRDA_STATE_READY
;
1197 /* As no DMA to be aborted, call directly user Abort complete callback */
1198 HAL_IRDA_AbortCpltCallback(hirda
);
1205 * @brief Abort ongoing Transmit transfer (Interrupt mode).
1206 * @param hirda IRDA handle.
1207 * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode.
1208 * This procedure performs following operations :
1209 * - Disable PPP Interrupts
1210 * - Disable the DMA transfer in the peripheral register (if enabled)
1211 * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode)
1212 * - Set handle State to READY
1213 * - At abort completion, call user abort complete callback
1214 * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be
1215 * considered as completed only when user abort complete callback is executed (not when exiting function).
1216 * @retval HAL status
1218 HAL_StatusTypeDef
HAL_IRDA_AbortTransmit_IT(IRDA_HandleTypeDef
*hirda
)
1220 /* Disable TXEIE and TCIE interrupts */
1221 CLEAR_BIT(hirda
->Instance
->CR1
, (USART_CR1_TXEIE
| USART_CR1_TCIE
));
1223 /* Disable the IRDA DMA Tx request if enabled */
1224 if(HAL_IS_BIT_SET(hirda
->Instance
->CR3
, USART_CR3_DMAT
))
1226 CLEAR_BIT(hirda
->Instance
->CR3
, USART_CR3_DMAT
);
1228 /* Abort the IRDA DMA Tx channel : use blocking DMA Abort API (no callback) */
1229 if(hirda
->hdmatx
!= NULL
)
1231 /* Set the IRDA DMA Abort callback :
1232 will lead to call HAL_IRDA_AbortCpltCallback() at end of DMA abort procedure */
1233 hirda
->hdmatx
->XferAbortCallback
= IRDA_DMATxOnlyAbortCallback
;
1236 if(HAL_DMA_Abort_IT(hirda
->hdmatx
) != HAL_OK
)
1238 /* Call Directly hirda->hdmatx->XferAbortCallback function in case of error */
1239 hirda
->hdmatx
->XferAbortCallback(hirda
->hdmatx
);
1244 /* Reset Tx transfer counter */
1245 hirda
->TxXferCount
= 0x00U
;
1247 /* Restore hirda->gState to Ready */
1248 hirda
->gState
= HAL_IRDA_STATE_READY
;
1250 /* As no DMA to be aborted, call directly user Abort complete callback */
1251 HAL_IRDA_AbortTransmitCpltCallback(hirda
);
1256 /* Reset Tx transfer counter */
1257 hirda
->TxXferCount
= 0x00U
;
1259 /* Restore hirda->gState to Ready */
1260 hirda
->gState
= HAL_IRDA_STATE_READY
;
1262 /* As no DMA to be aborted, call directly user Abort complete callback */
1263 HAL_IRDA_AbortTransmitCpltCallback(hirda
);
1270 * @brief Abort ongoing Receive transfer (Interrupt mode).
1271 * @param hirda IRDA handle.
1272 * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode.
1273 * This procedure performs following operations :
1274 * - Disable PPP Interrupts
1275 * - Disable the DMA transfer in the peripheral register (if enabled)
1276 * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode)
1277 * - Set handle State to READY
1278 * - At abort completion, call user abort complete callback
1279 * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be
1280 * considered as completed only when user abort complete callback is executed (not when exiting function).
1281 * @retval HAL status
1283 HAL_StatusTypeDef
HAL_IRDA_AbortReceive_IT(IRDA_HandleTypeDef
*hirda
)
1285 /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */
1286 CLEAR_BIT(hirda
->Instance
->CR1
, (USART_CR1_RXNEIE
| USART_CR1_PEIE
));
1287 CLEAR_BIT(hirda
->Instance
->CR3
, USART_CR3_EIE
);
1289 /* Disable the IRDA DMA Rx request if enabled */
1290 if(HAL_IS_BIT_SET(hirda
->Instance
->CR3
, USART_CR3_DMAR
))
1292 CLEAR_BIT(hirda
->Instance
->CR3
, USART_CR3_DMAR
);
1294 /* Abort the IRDA DMA Rx channel : use blocking DMA Abort API (no callback) */
1295 if(hirda
->hdmarx
!= NULL
)
1297 /* Set the IRDA DMA Abort callback :
1298 will lead to call HAL_IRDA_AbortCpltCallback() at end of DMA abort procedure */
1299 hirda
->hdmarx
->XferAbortCallback
= IRDA_DMARxOnlyAbortCallback
;
1302 if(HAL_DMA_Abort_IT(hirda
->hdmarx
) != HAL_OK
)
1304 /* Call Directly hirda->hdmarx->XferAbortCallback function in case of error */
1305 hirda
->hdmarx
->XferAbortCallback(hirda
->hdmarx
);
1310 /* Reset Rx transfer counter */
1311 hirda
->RxXferCount
= 0x00U
;
1313 /* Restore hirda->RxState to Ready */
1314 hirda
->RxState
= HAL_IRDA_STATE_READY
;
1316 /* As no DMA to be aborted, call directly user Abort complete callback */
1317 HAL_IRDA_AbortReceiveCpltCallback(hirda
);
1322 /* Reset Rx transfer counter */
1323 hirda
->RxXferCount
= 0x00U
;
1325 /* Restore hirda->RxState to Ready */
1326 hirda
->RxState
= HAL_IRDA_STATE_READY
;
1328 /* As no DMA to be aborted, call directly user Abort complete callback */
1329 HAL_IRDA_AbortReceiveCpltCallback(hirda
);
1336 * @brief This function handles IRDA interrupt request.
1337 * @param hirda: Pointer to a IRDA_HandleTypeDef structure that contains
1338 * the configuration information for the specified IRDA module.
1341 void HAL_IRDA_IRQHandler(IRDA_HandleTypeDef
*hirda
)
1343 uint32_t isrflags
= READ_REG(hirda
->Instance
->SR
);
1344 uint32_t cr1its
= READ_REG(hirda
->Instance
->CR1
);
1345 uint32_t cr3its
= READ_REG(hirda
->Instance
->CR3
);
1346 uint32_t errorflags
= 0x00U
;
1347 uint32_t dmarequest
= 0x00U
;
1349 /* If no error occurs */
1350 errorflags
= (isrflags
& (uint32_t)(USART_SR_PE
| USART_SR_FE
| USART_SR_ORE
| USART_SR_NE
));
1351 if(errorflags
== RESET
)
1353 /* IRDA in mode Receiver -----------------------------------------------*/
1354 if(((isrflags
& USART_SR_RXNE
) != RESET
) && ((cr1its
& USART_CR1_RXNEIE
) != RESET
))
1356 IRDA_Receive_IT(hirda
);
1361 /* If some errors occur */
1362 if((errorflags
!= RESET
) && (((cr3its
& USART_CR3_EIE
) != RESET
) || ((cr1its
& (USART_CR1_RXNEIE
| USART_CR1_PEIE
)) != RESET
)))
1364 /* IRDA parity error interrupt occurred -------------------------------*/
1365 if(((isrflags
& USART_SR_PE
) != RESET
) && ((cr1its
& USART_CR1_PEIE
) != RESET
))
1367 hirda
->ErrorCode
|= HAL_IRDA_ERROR_PE
;
1370 /* IRDA noise error interrupt occurred --------------------------------*/
1371 if(((isrflags
& USART_SR_NE
) != RESET
) && ((cr3its
& USART_CR3_EIE
) != RESET
))
1373 hirda
->ErrorCode
|= HAL_IRDA_ERROR_NE
;
1376 /* IRDA frame error interrupt occurred --------------------------------*/
1377 if(((isrflags
& USART_SR_FE
) != RESET
) && ((cr3its
& USART_CR3_EIE
) != RESET
))
1379 hirda
->ErrorCode
|= HAL_IRDA_ERROR_FE
;
1382 /* IRDA Over-Run interrupt occurred -----------------------------------*/
1383 if(((isrflags
& USART_SR_ORE
) != RESET
) && ((cr3its
& USART_CR3_EIE
) != RESET
))
1385 hirda
->ErrorCode
|= HAL_IRDA_ERROR_ORE
;
1387 /* Call IRDA Error Call back function if need be -----------------------*/
1388 if(hirda
->ErrorCode
!= HAL_IRDA_ERROR_NONE
)
1390 /* IRDA in mode Receiver ---------------------------------------------*/
1391 if(((isrflags
& USART_SR_RXNE
) != RESET
) && ((cr1its
& USART_CR1_RXNEIE
) != RESET
))
1393 IRDA_Receive_IT(hirda
);
1396 /* If Overrun error occurs, or if any error occurs in DMA mode reception,
1397 consider error as blocking */
1398 dmarequest
= HAL_IS_BIT_SET(hirda
->Instance
->CR3
, USART_CR3_DMAR
);
1399 if(((hirda
->ErrorCode
& HAL_IRDA_ERROR_ORE
) != RESET
) || dmarequest
)
1401 /* Blocking error : transfer is aborted
1402 Set the IRDA state ready to be able to start again the process,
1403 Disable Rx Interrupts, and disable Rx DMA request, if ongoing */
1404 IRDA_EndRxTransfer(hirda
);
1406 /* Disable the IRDA DMA Rx request if enabled */
1407 if(HAL_IS_BIT_SET(hirda
->Instance
->CR3
, USART_CR3_DMAR
))
1409 CLEAR_BIT(hirda
->Instance
->CR3
, USART_CR3_DMAR
);
1411 /* Abort the IRDA DMA Rx channel */
1412 if(hirda
->hdmarx
!= NULL
)
1414 /* Set the IRDA DMA Abort callback :
1415 will lead to call HAL_IRDA_ErrorCallback() at end of DMA abort procedure */
1416 hirda
->hdmarx
->XferAbortCallback
= IRDA_DMAAbortOnError
;
1418 if(HAL_DMA_Abort_IT(hirda
->hdmarx
) != HAL_OK
)
1420 /* Call Directly XferAbortCallback function in case of error */
1421 hirda
->hdmarx
->XferAbortCallback(hirda
->hdmarx
);
1426 /* Call user error callback */
1427 HAL_IRDA_ErrorCallback(hirda
);
1432 /* Call user error callback */
1433 HAL_IRDA_ErrorCallback(hirda
);
1438 /* Non Blocking error : transfer could go on.
1439 Error is notified to user through user error callback */
1440 HAL_IRDA_ErrorCallback(hirda
);
1441 hirda
->ErrorCode
= HAL_IRDA_ERROR_NONE
;
1445 } /* End if some error occurs */
1447 /* IRDA in mode Transmitter ------------------------------------------------*/
1448 if(((isrflags
& USART_SR_TXE
) != RESET
) && ((cr1its
& USART_CR1_TXEIE
) != RESET
))
1450 IRDA_Transmit_IT(hirda
);
1454 /* IRDA in mode Transmitter end --------------------------------------------*/
1455 if(((isrflags
& USART_SR_TC
) != RESET
) && ((cr1its
& USART_CR1_TCIE
) != RESET
))
1457 IRDA_EndTransmit_IT(hirda
);
1463 * @brief Tx Transfer complete callbacks.
1464 * @param hirda: pointer to a IRDA_HandleTypeDef structure that contains
1465 * the configuration information for the specified IRDA module.
1468 __weak
void HAL_IRDA_TxCpltCallback(IRDA_HandleTypeDef
*hirda
)
1470 /* Prevent unused argument(s) compilation warning */
1472 /* NOTE: This function should not be modified, when the callback is needed,
1473 the HAL_IRDA_TxCpltCallback can be implemented in the user file
1478 * @brief Tx Half Transfer completed callbacks.
1479 * @param hirda: Pointer to a IRDA_HandleTypeDef structure that contains
1480 * the configuration information for the specified USART module.
1483 __weak
void HAL_IRDA_TxHalfCpltCallback(IRDA_HandleTypeDef
*hirda
)
1485 /* Prevent unused argument(s) compilation warning */
1487 /* NOTE: This function should not be modified, when the callback is needed,
1488 the HAL_IRDA_TxHalfCpltCallback can be implemented in the user file
1493 * @brief Rx Transfer complete callbacks.
1494 * @param hirda: Pointer to a IRDA_HandleTypeDef structure that contains
1495 * the configuration information for the specified IRDA module.
1498 __weak
void HAL_IRDA_RxCpltCallback(IRDA_HandleTypeDef
*hirda
)
1500 /* Prevent unused argument(s) compilation warning */
1502 /* NOTE: This function should not be modified, when the callback is needed,
1503 the HAL_IRDA_RxCpltCallback can be implemented in the user file
1508 * @brief Rx Half Transfer complete callbacks.
1509 * @param hirda: Pointer to a IRDA_HandleTypeDef structure that contains
1510 * the configuration information for the specified IRDA module.
1513 __weak
void HAL_IRDA_RxHalfCpltCallback(IRDA_HandleTypeDef
*hirda
)
1515 /* Prevent unused argument(s) compilation warning */
1517 /* NOTE : This function should not be modified, when the callback is needed,
1518 the HAL_IRDA_RxHalfCpltCallback can be implemented in the user file
1523 * @brief IRDA error callbacks.
1524 * @param hirda: Pointer to a IRDA_HandleTypeDef structure that contains
1525 * the configuration information for the specified IRDA module.
1528 __weak
void HAL_IRDA_ErrorCallback(IRDA_HandleTypeDef
*hirda
)
1530 /* Prevent unused argument(s) compilation warning */
1532 /* NOTE : This function Should not be modified, when the callback is needed,
1533 the HAL_IRDA_ErrorCallback could be implemented in the user file
1538 * @brief IRDA Abort Complete callback.
1539 * @param hirda IRDA handle.
1542 __weak
void HAL_IRDA_AbortCpltCallback(IRDA_HandleTypeDef
*hirda
)
1544 /* Prevent unused argument(s) compilation warning */
1547 /* NOTE : This function should not be modified, when the callback is needed,
1548 the HAL_IRDA_AbortCpltCallback can be implemented in the user file.
1553 * @brief IRDA Abort Transmit Complete callback.
1554 * @param hirda IRDA handle.
1557 __weak
void HAL_IRDA_AbortTransmitCpltCallback(IRDA_HandleTypeDef
*hirda
)
1559 /* Prevent unused argument(s) compilation warning */
1562 /* NOTE : This function should not be modified, when the callback is needed,
1563 the HAL_IRDA_AbortTransmitCpltCallback can be implemented in the user file.
1568 * @brief IRDA Abort ReceiveComplete callback.
1569 * @param hirda IRDA handle.
1572 __weak
void HAL_IRDA_AbortReceiveCpltCallback(IRDA_HandleTypeDef
*hirda
)
1574 /* Prevent unused argument(s) compilation warning */
1577 /* NOTE : This function should not be modified, when the callback is needed,
1578 the HAL_IRDA_AbortReceiveCpltCallback can be implemented in the user file.
1586 /** @defgroup IRDA_Exported_Functions_Group3 Peripheral State and Errors functions
1587 * @brief IRDA State and Errors functions
1590 ==============================================================================
1591 ##### Peripheral State and Errors functions #####
1592 ==============================================================================
1594 This subsection provides a set of functions allowing to return the State of IrDA
1595 communication process and also return Peripheral Errors occurred during communication process
1596 (+) HAL_IRDA_GetState() API can be helpful to check in run-time the state of the IrDA peripheral.
1597 (+) HAL_IRDA_GetError() check in run-time errors that could be occurred during communication.
1604 * @brief Returns the IRDA state.
1605 * @param hirda: Pointer to a IRDA_HandleTypeDef structure that contains
1606 * the configuration information for the specified IRDA module.
1609 HAL_IRDA_StateTypeDef
HAL_IRDA_GetState(IRDA_HandleTypeDef
*hirda
)
1611 uint32_t temp1
= 0x00U
, temp2
= 0x00U
;
1612 temp1
= hirda
->gState
;
1613 temp2
= hirda
->RxState
;
1615 return (HAL_IRDA_StateTypeDef
)(temp1
| temp2
);
1619 * @brief Return the IRDA error code
1620 * @param hirda: Pointer to a IRDA_HandleTypeDef structure that contains
1621 * the configuration information for the specified IRDA module.
1622 * @retval IRDA Error Code
1624 uint32_t HAL_IRDA_GetError(IRDA_HandleTypeDef
*hirda
)
1626 return hirda
->ErrorCode
;
1634 * @brief DMA IRDA transmit process complete callback.
1635 * @param hdma: Pointer to a DMA_HandleTypeDef structure that contains
1636 * the configuration information for the specified DMA module.
1639 static void IRDA_DMATransmitCplt(DMA_HandleTypeDef
*hdma
)
1641 IRDA_HandleTypeDef
* hirda
= ( IRDA_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
1642 /* DMA Normal mode */
1643 if((hdma
->Instance
->CCR
& DMA_CCR_CIRC
) == 0U)
1645 hirda
->TxXferCount
= 0U;
1647 /* Disable the DMA transfer for transmit request by setting the DMAT bit
1648 in the IRDA CR3 register */
1649 CLEAR_BIT(hirda
->Instance
->CR3
, USART_CR3_DMAT
);
1651 /* Enable the IRDA Transmit Complete Interrupt */
1652 __HAL_IRDA_ENABLE_IT(hirda
, IRDA_IT_TC
);
1654 /* DMA Circular mode */
1657 HAL_IRDA_TxCpltCallback(hirda
);
1662 * @brief DMA IRDA receive process half complete callback
1663 * @param hdma: Pointer to a DMA_HandleTypeDef structure that contains
1664 * the configuration information for the specified DMA module.
1667 static void IRDA_DMATransmitHalfCplt(DMA_HandleTypeDef
*hdma
)
1669 IRDA_HandleTypeDef
* hirda
= ( IRDA_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
1671 HAL_IRDA_TxHalfCpltCallback(hirda
);
1675 * @brief DMA IRDA receive process complete callback.
1676 * @param hdma: DMA handle
1679 static void IRDA_DMAReceiveCplt(DMA_HandleTypeDef
*hdma
)
1681 IRDA_HandleTypeDef
* hirda
= ( IRDA_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
1682 /* DMA Normal mode */
1683 if((hdma
->Instance
->CCR
& DMA_CCR_CIRC
) == 0U)
1685 hirda
->RxXferCount
= 0U;
1687 /* Disable PE and ERR (Frame error, noise error, overrun error) interrupts */
1688 CLEAR_BIT(hirda
->Instance
->CR1
, USART_CR1_PEIE
);
1689 CLEAR_BIT(hirda
->Instance
->CR3
, USART_CR3_EIE
);
1691 /* Disable the DMA transfer for the receiver request by setting the DMAR bit
1692 in the IRDA CR3 register */
1693 CLEAR_BIT(hirda
->Instance
->CR3
, USART_CR3_DMAR
);
1695 /* At end of Rx process, restore hirda->RxState to Ready */
1696 hirda
->RxState
= HAL_IRDA_STATE_READY
;
1698 HAL_IRDA_RxCpltCallback(hirda
);
1702 * @brief DMA IRDA receive process half complete callback
1703 * @param hdma: Pointer to a DMA_HandleTypeDef structure that contains
1704 * the configuration information for the specified DMA module.
1707 static void IRDA_DMAReceiveHalfCplt(DMA_HandleTypeDef
*hdma
)
1709 IRDA_HandleTypeDef
* hirda
= ( IRDA_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
1710 HAL_IRDA_RxHalfCpltCallback(hirda
);
1714 * @brief DMA IRDA communication error callback.
1715 * @param hdma: DMA handle
1718 static void IRDA_DMAError(DMA_HandleTypeDef
*hdma
)
1720 uint32_t dmarequest
= 0x00U
;
1721 IRDA_HandleTypeDef
* hirda
= ( IRDA_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
1723 /* Stop IRDA DMA Tx request if ongoing */
1724 dmarequest
= HAL_IS_BIT_SET(hirda
->Instance
->CR3
, USART_CR3_DMAT
);
1725 if((hirda
->gState
== HAL_IRDA_STATE_BUSY_TX
) && dmarequest
)
1727 hirda
->TxXferCount
= 0U;
1728 IRDA_EndTxTransfer(hirda
);
1731 /* Stop IRDA DMA Rx request if ongoing */
1732 dmarequest
= HAL_IS_BIT_SET(hirda
->Instance
->CR3
, USART_CR3_DMAR
);
1733 if((hirda
->RxState
== HAL_IRDA_STATE_BUSY_RX
) && dmarequest
)
1735 hirda
->RxXferCount
= 0U;
1736 IRDA_EndRxTransfer(hirda
);
1739 hirda
->ErrorCode
|= HAL_IRDA_ERROR_DMA
;
1741 HAL_IRDA_ErrorCallback(hirda
);
1745 * @brief This function handles IRDA Communication Timeout.
1746 * @param hirda: Pointer to a IRDA_HandleTypeDef structure that contains
1747 * the configuration information for the specified IRDA module.
1748 * @param Flag: specifies the IRDA flag to check.
1749 * @param Status: The new Flag status (SET or RESET).
1750 * @param Tickstart: Tick start value
1751 * @param Timeout: Timeout duration
1752 * @retval HAL status
1754 static HAL_StatusTypeDef
IRDA_WaitOnFlagUntilTimeout(IRDA_HandleTypeDef
*hirda
, uint32_t Flag
, FlagStatus Status
, uint32_t Tickstart
, uint32_t Timeout
)
1756 /* Wait until flag is set */
1757 while((__HAL_IRDA_GET_FLAG(hirda
, Flag
) ? SET
: RESET
) == Status
)
1759 /* Check for the Timeout */
1760 if(Timeout
!= HAL_MAX_DELAY
)
1762 if((Timeout
== 0U)||((HAL_GetTick() - Tickstart
) > Timeout
))
1764 /* Disable TXE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts for the interrupt process */
1765 CLEAR_BIT(hirda
->Instance
->CR1
, (USART_CR1_RXNEIE
| USART_CR1_PEIE
| USART_CR1_TXEIE
));
1766 CLEAR_BIT(hirda
->Instance
->CR3
, USART_CR3_EIE
);
1768 hirda
->gState
= HAL_IRDA_STATE_READY
;
1769 hirda
->RxState
= HAL_IRDA_STATE_READY
;
1771 /* Process Unlocked */
1772 __HAL_UNLOCK(hirda
);
1782 * @brief End ongoing Tx transfer on IRDA peripheral (following error detection or Transmit completion).
1783 * @param hirda: IRDA handle.
1786 static void IRDA_EndTxTransfer(IRDA_HandleTypeDef
*hirda
)
1788 /* Disable TXEIE and TCIE interrupts */
1789 CLEAR_BIT(hirda
->Instance
->CR1
, (USART_CR1_TXEIE
| USART_CR1_TCIE
));
1791 /* At end of Tx process, restore hirda->gState to Ready */
1792 hirda
->gState
= HAL_IRDA_STATE_READY
;
1796 * @brief End ongoing Rx transfer on IRDA peripheral (following error detection or Reception completion).
1797 * @param hirda: IRDA handle.
1800 static void IRDA_EndRxTransfer(IRDA_HandleTypeDef
*hirda
)
1802 /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */
1803 CLEAR_BIT(hirda
->Instance
->CR1
, (USART_CR1_RXNEIE
| USART_CR1_PEIE
));
1804 CLEAR_BIT(hirda
->Instance
->CR3
, USART_CR3_EIE
);
1806 /* At end of Rx process, restore hirda->RxState to Ready */
1807 hirda
->RxState
= HAL_IRDA_STATE_READY
;
1811 * @brief DMA IRDA communication abort callback, when initiated by HAL services on Error
1812 * (To be called at end of DMA Abort procedure following error occurrence).
1813 * @param hdma DMA handle.
1816 static void IRDA_DMAAbortOnError(DMA_HandleTypeDef
*hdma
)
1818 IRDA_HandleTypeDef
* hirda
= ( IRDA_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
1819 hirda
->RxXferCount
= 0x00U
;
1820 hirda
->TxXferCount
= 0x00U
;
1822 HAL_IRDA_ErrorCallback(hirda
);
1826 * @brief DMA IRDA Tx communication abort callback, when initiated by user
1827 * (To be called at end of DMA Tx Abort procedure following user abort request).
1828 * @note When this callback is executed, User Abort complete call back is called only if no
1829 * Abort still ongoing for Rx DMA Handle.
1830 * @param hdma DMA handle.
1833 static void IRDA_DMATxAbortCallback(DMA_HandleTypeDef
*hdma
)
1835 IRDA_HandleTypeDef
* hirda
= ( IRDA_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
1837 hirda
->hdmatx
->XferAbortCallback
= NULL
;
1839 /* Check if an Abort process is still ongoing */
1840 if(hirda
->hdmarx
!= NULL
)
1842 if(hirda
->hdmarx
->XferAbortCallback
!= NULL
)
1848 /* No Abort process still ongoing : All DMA channels are aborted, call user Abort Complete callback */
1849 hirda
->TxXferCount
= 0x00U
;
1850 hirda
->RxXferCount
= 0x00U
;
1852 /* Reset ErrorCode */
1853 hirda
->ErrorCode
= HAL_IRDA_ERROR_NONE
;
1855 /* Restore hirda->gState and hirda->RxState to Ready */
1856 hirda
->gState
= HAL_IRDA_STATE_READY
;
1857 hirda
->RxState
= HAL_IRDA_STATE_READY
;
1859 /* Call user Abort complete callback */
1860 HAL_IRDA_AbortCpltCallback(hirda
);
1864 * @brief DMA IRDA Rx communication abort callback, when initiated by user
1865 * (To be called at end of DMA Rx Abort procedure following user abort request).
1866 * @note When this callback is executed, User Abort complete call back is called only if no
1867 * Abort still ongoing for Tx DMA Handle.
1868 * @param hdma DMA handle.
1871 static void IRDA_DMARxAbortCallback(DMA_HandleTypeDef
*hdma
)
1873 IRDA_HandleTypeDef
* hirda
= ( IRDA_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
1875 hirda
->hdmarx
->XferAbortCallback
= NULL
;
1877 /* Check if an Abort process is still ongoing */
1878 if(hirda
->hdmatx
!= NULL
)
1880 if(hirda
->hdmatx
->XferAbortCallback
!= NULL
)
1886 /* No Abort process still ongoing : All DMA channels are aborted, call user Abort Complete callback */
1887 hirda
->TxXferCount
= 0x00U
;
1888 hirda
->RxXferCount
= 0x00U
;
1890 /* Reset ErrorCode */
1891 hirda
->ErrorCode
= HAL_IRDA_ERROR_NONE
;
1893 /* Restore hirda->gState and hirda->RxState to Ready */
1894 hirda
->gState
= HAL_IRDA_STATE_READY
;
1895 hirda
->RxState
= HAL_IRDA_STATE_READY
;
1897 /* Call user Abort complete callback */
1898 HAL_IRDA_AbortCpltCallback(hirda
);
1902 * @brief DMA IRDA Tx communication abort callback, when initiated by user by a call to
1903 * HAL_IRDA_AbortTransmit_IT API (Abort only Tx transfer)
1904 * (This callback is executed at end of DMA Tx Abort procedure following user abort request,
1905 * and leads to user Tx Abort Complete callback execution).
1906 * @param hdma DMA handle.
1909 static void IRDA_DMATxOnlyAbortCallback(DMA_HandleTypeDef
*hdma
)
1911 IRDA_HandleTypeDef
* hirda
= ( IRDA_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
1913 hirda
->TxXferCount
= 0x00U
;
1915 /* Restore hirda->gState to Ready */
1916 hirda
->gState
= HAL_IRDA_STATE_READY
;
1918 /* Call user Abort complete callback */
1919 HAL_IRDA_AbortTransmitCpltCallback(hirda
);
1923 * @brief DMA IRDA Rx communication abort callback, when initiated by user by a call to
1924 * HAL_IRDA_AbortReceive_IT API (Abort only Rx transfer)
1925 * (This callback is executed at end of DMA Rx Abort procedure following user abort request,
1926 * and leads to user Rx Abort Complete callback execution).
1927 * @param hdma DMA handle.
1930 static void IRDA_DMARxOnlyAbortCallback(DMA_HandleTypeDef
*hdma
)
1932 IRDA_HandleTypeDef
* hirda
= ( IRDA_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
1934 hirda
->RxXferCount
= 0x00U
;
1936 /* Restore hirda->RxState to Ready */
1937 hirda
->RxState
= HAL_IRDA_STATE_READY
;
1939 /* Call user Abort complete callback */
1940 HAL_IRDA_AbortReceiveCpltCallback(hirda
);
1944 * @brief Send an amount of data in non blocking mode.
1945 * @param hirda: pointer to a IRDA_HandleTypeDef structure that contains
1946 * the configuration information for the specified IRDA module.
1947 * @retval HAL status
1949 static HAL_StatusTypeDef
IRDA_Transmit_IT(IRDA_HandleTypeDef
*hirda
)
1953 /* Check that a Tx process is ongoing */
1954 if(hirda
->gState
== HAL_IRDA_STATE_BUSY_TX
)
1956 if(hirda
->Init
.WordLength
== IRDA_WORDLENGTH_9B
)
1958 tmp
= (uint16_t*) hirda
->pTxBuffPtr
;
1959 hirda
->Instance
->DR
= (uint16_t)(*tmp
& (uint16_t)0x01FF);
1960 if(hirda
->Init
.Parity
== IRDA_PARITY_NONE
)
1962 hirda
->pTxBuffPtr
+= 2U;
1966 hirda
->pTxBuffPtr
+= 1U;
1971 hirda
->Instance
->DR
= (uint8_t)(*hirda
->pTxBuffPtr
++ & (uint8_t)0x00FF);
1974 if(--hirda
->TxXferCount
== 0U)
1976 /* Disable the IRDA Transmit Data Register Empty Interrupt */
1977 CLEAR_BIT(hirda
->Instance
->CR1
, USART_CR1_TXEIE
);
1979 /* Enable the IRDA Transmit Complete Interrupt */
1980 SET_BIT(hirda
->Instance
->CR1
, USART_CR1_TCIE
);
1991 * @brief Wraps up transmission in non blocking mode.
1992 * @param hirda: pointer to a IRDA_HandleTypeDef structure that contains
1993 * the configuration information for the specified IRDA module.
1994 * @retval HAL status
1996 static HAL_StatusTypeDef
IRDA_EndTransmit_IT(IRDA_HandleTypeDef
*hirda
)
1998 /* Disable the IRDA Transmit Complete Interrupt */
1999 CLEAR_BIT(hirda
->Instance
->CR1
, USART_CR1_TCIE
);
2001 /* Tx process is ended, restore hirda->gState to Ready */
2002 hirda
->gState
= HAL_IRDA_STATE_READY
;
2003 HAL_IRDA_TxCpltCallback(hirda
);
2009 * @brief Receives an amount of data in non blocking mode.
2010 * @param hirda: Pointer to a IRDA_HandleTypeDef structure that contains
2011 * the configuration information for the specified IRDA module.
2012 * @retval HAL status
2014 static HAL_StatusTypeDef
IRDA_Receive_IT(IRDA_HandleTypeDef
*hirda
)
2019 /* Check that a Rx process is ongoing */
2020 if(hirda
->RxState
== HAL_IRDA_STATE_BUSY_RX
)
2022 uhdata
= (uint16_t) READ_REG(hirda
->Instance
->DR
);
2023 if(hirda
->Init
.WordLength
== IRDA_WORDLENGTH_9B
)
2025 tmp
= (uint16_t*) hirda
->pRxBuffPtr
;
2026 if(hirda
->Init
.Parity
== IRDA_PARITY_NONE
)
2028 *tmp
= (uint16_t)(uhdata
& (uint16_t)0x01FF);
2029 hirda
->pRxBuffPtr
+= 2U;
2033 *tmp
= (uint16_t)(uhdata
& (uint16_t)0x00FF);
2034 hirda
->pRxBuffPtr
+= 1U;
2039 if(hirda
->Init
.Parity
== IRDA_PARITY_NONE
)
2041 *hirda
->pRxBuffPtr
++ = (uint8_t)(uhdata
& (uint8_t)0x00FF);
2045 *hirda
->pRxBuffPtr
++ = (uint8_t)(uhdata
& (uint8_t)0x007F);
2049 if(--hirda
->RxXferCount
== 0U)
2051 /* Disable the IRDA Data Register not empty Interrupt */
2052 __HAL_IRDA_DISABLE_IT(hirda
, IRDA_IT_RXNE
);
2054 /* Disable the IRDA Parity Error Interrupt */
2055 __HAL_IRDA_DISABLE_IT(hirda
, IRDA_IT_PE
);
2057 /* Disable the IRDA Error Interrupt: (Frame error, noise error, overrun error) */
2058 __HAL_IRDA_DISABLE_IT(hirda
, IRDA_IT_ERR
);
2060 /* Rx process is completed, restore hirda->RxState to Ready */
2061 hirda
->RxState
= HAL_IRDA_STATE_READY
;
2062 HAL_IRDA_RxCpltCallback(hirda
);
2075 * @brief Configures the IRDA peripheral.
2076 * @param hirda: Pointer to a IRDA_HandleTypeDef structure that contains
2077 * the configuration information for the specified IRDA module.
2080 static void IRDA_SetConfig(IRDA_HandleTypeDef
*hirda
)
2082 /* Check the parameters */
2083 assert_param(IS_IRDA_INSTANCE(hirda
->Instance
));
2084 assert_param(IS_IRDA_BAUDRATE(hirda
->Init
.BaudRate
));
2085 assert_param(IS_IRDA_WORD_LENGTH(hirda
->Init
.WordLength
));
2086 assert_param(IS_IRDA_PARITY(hirda
->Init
.Parity
));
2087 assert_param(IS_IRDA_MODE(hirda
->Init
.Mode
));
2088 assert_param(IS_IRDA_POWERMODE(hirda
->Init
.IrDAMode
));
2090 /*-------------------------- USART CR2 Configuration ------------------------*/
2091 /* Clear STOP[13:12] bits */
2092 CLEAR_BIT(hirda
->Instance
->CR2
, USART_CR2_STOP
);
2094 /*-------------------------- USART CR1 Configuration -----------------------*/
2095 /* Clear M, PCE, PS, TE and RE bits */
2096 CLEAR_BIT(hirda
->Instance
->CR1
, USART_CR1_M
| USART_CR1_PCE
| USART_CR1_PS
| USART_CR1_TE
| USART_CR1_RE
);
2098 /* Configure the USART Word Length, Parity and mode:
2099 Set the M bits according to hirda->Init.WordLength value
2100 Set PCE and PS bits according to hirda->Init.Parity value
2101 Set TE and RE bits according to hirda->Init.Mode value */
2102 /* Write to USART CR1 */
2103 SET_BIT(hirda
->Instance
->CR1
, (uint32_t)hirda
->Init
.WordLength
| hirda
->Init
.Parity
| hirda
->Init
.Mode
);
2105 /*-------------------------- USART CR3 Configuration -----------------------*/
2106 /* Clear CTSE and RTSE bits */
2107 CLEAR_BIT(hirda
->Instance
->CR3
, USART_CR3_RTSE
| USART_CR3_CTSE
);
2109 /*-------------------------- USART BRR Configuration -----------------------*/
2110 if(hirda
->Instance
== USART1
)
2112 SET_BIT(hirda
->Instance
->BRR
, IRDA_BRR(HAL_RCC_GetPCLK2Freq(), hirda
->Init
.BaudRate
));
2116 SET_BIT(hirda
->Instance
->BRR
, IRDA_BRR(HAL_RCC_GetPCLK1Freq(), hirda
->Init
.BaudRate
));
2124 #endif /* HAL_IRDA_MODULE_ENABLED */
2133 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/