2 ******************************************************************************
3 * @file stm32f1xx_hal_irda.h
4 * @author MCD Application Team
7 * @brief Header file of IRDA HAL module.
8 ******************************************************************************
11 * <h2><center>© COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
13 * Redistribution and use in source and binary forms, with or without modification,
14 * are permitted provided that the following conditions are met:
15 * 1. Redistributions of source code must retain the above copyright notice,
16 * this list of conditions and the following disclaimer.
17 * 2. Redistributions in binary form must reproduce the above copyright notice,
18 * this list of conditions and the following disclaimer in the documentation
19 * and/or other materials provided with the distribution.
20 * 3. Neither the name of STMicroelectronics nor the names of its contributors
21 * may be used to endorse or promote products derived from this software
22 * without specific prior written permission.
24 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
25 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
26 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
27 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
28 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
29 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
30 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
32 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
33 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
35 ******************************************************************************
38 /* Define to prevent recursive inclusion -------------------------------------*/
39 #ifndef __STM32F1xx_HAL_IRDA_H
40 #define __STM32F1xx_HAL_IRDA_H
46 /* Includes ------------------------------------------------------------------*/
47 #include "stm32f1xx_hal_def.h"
49 /** @addtogroup STM32F1xx_HAL_Driver
57 /* Exported types ------------------------------------------------------------*/
58 /** @defgroup IRDA_Exported_Types IRDA Exported Types
63 * @brief IRDA Init Structure definition
67 uint32_t BaudRate
; /*!< This member configures the IRDA communication baud rate.
68 The baud rate is computed using the following formula:
69 - IntegerDivider = ((PCLKx) / (16 * (hirda->Init.BaudRate)))
70 - FractionalDivider = ((IntegerDivider - ((uint32_t) IntegerDivider)) * 16) + 0.5 */
72 uint32_t WordLength
; /*!< Specifies the number of data bits transmitted or received in a frame.
73 This parameter can be a value of @ref IRDA_Word_Length */
76 uint32_t Parity
; /*!< Specifies the parity mode.
77 This parameter can be a value of @ref IRDA_Parity
78 @note When parity is enabled, the computed parity is inserted
79 at the MSB position of the transmitted data (9th bit when
80 the word length is set to 9 data bits; 8th bit when the
81 word length is set to 8 data bits). */
83 uint32_t Mode
; /*!< Specifies whether the Receive or Transmit mode is enabled or disabled.
84 This parameter can be a value of @ref IRDA_Transfer_Mode */
86 uint8_t Prescaler
; /*!< Specifies the Prescaler value prescaler value to be programmed
87 in the IrDA low-power Baud Register, for defining pulse width on which
88 burst acceptance/rejection will be decided. This value is used as divisor
89 of system clock to achieve required pulse width. */
91 uint32_t IrDAMode
; /*!< Specifies the IrDA mode
92 This parameter can be a value of @ref IRDA_Low_Power */
96 * @brief HAL IRDA State structures definition
97 * @note HAL IRDA State value is a combination of 2 different substates: gState and RxState.
98 * - gState contains IRDA state information related to global Handle management
99 * and also information related to Tx operations.
100 * gState value coding follow below described bitmap :
101 * b7-b6 Error information
106 * b5 IP initilisation status
107 * 0 : Reset (IP not initialized)
108 * 1 : Init done (IP not initialized. HAL IRDA Init function already called)
110 * xx : Should be set to 00
111 * b2 Intrinsic process state
113 * 1 : Busy (IP busy with some configuration or internal operations)
115 * x : Should be set to 0
117 * 0 : Ready (no Tx operation ongoing)
118 * 1 : Busy (Tx operation ongoing)
119 * - RxState contains information related to Rx operations.
120 * RxState value coding follow below described bitmap :
122 * xx : Should be set to 00
123 * b5 IP initilisation status
124 * 0 : Reset (IP not initialized)
125 * 1 : Init done (IP not initialized)
127 * xxx : Should be set to 000
129 * 0 : Ready (no Rx operation ongoing)
130 * 1 : Busy (Rx operation ongoing)
132 * x : Should be set to 0.
136 HAL_IRDA_STATE_RESET
= 0x00U
, /*!< Peripheral is not yet Initialized
137 Value is allowed for gState and RxState */
138 HAL_IRDA_STATE_READY
= 0x20U
, /*!< Peripheral Initialized and ready for use
139 Value is allowed for gState and RxState */
140 HAL_IRDA_STATE_BUSY
= 0x24U
, /*!< An internal process is ongoing
141 Value is allowed for gState only */
142 HAL_IRDA_STATE_BUSY_TX
= 0x21U
, /*!< Data Transmission process is ongoing
143 Value is allowed for gState only */
144 HAL_IRDA_STATE_BUSY_RX
= 0x22U
, /*!< Data Reception process is ongoing
145 Value is allowed for RxState only */
146 HAL_IRDA_STATE_BUSY_TX_RX
= 0x23U
, /*!< Data Transmission and Reception process is ongoing
147 Not to be used for neither gState nor RxState.
148 Value is result of combination (Or) between gState and RxState values */
149 HAL_IRDA_STATE_TIMEOUT
= 0xA0U
, /*!< Timeout state
150 Value is allowed for gState only */
151 HAL_IRDA_STATE_ERROR
= 0xE0U
/*!< Error
152 Value is allowed for gState only */
153 }HAL_IRDA_StateTypeDef
;
156 * @brief IRDA handle Structure definition
160 USART_TypeDef
*Instance
; /*!< USART registers base address */
162 IRDA_InitTypeDef Init
; /*!< IRDA communication parameters */
164 uint8_t *pTxBuffPtr
; /*!< Pointer to IRDA Tx transfer Buffer */
166 uint16_t TxXferSize
; /*!< IRDA Tx Transfer size */
168 __IO
uint16_t TxXferCount
; /*!< IRDA Tx Transfer Counter */
170 uint8_t *pRxBuffPtr
; /*!< Pointer to IRDA Rx transfer Buffer */
172 uint16_t RxXferSize
; /*!< IRDA Rx Transfer size */
174 __IO
uint16_t RxXferCount
; /*!< IRDA Rx Transfer Counter */
176 DMA_HandleTypeDef
*hdmatx
; /*!< IRDA Tx DMA Handle parameters */
178 DMA_HandleTypeDef
*hdmarx
; /*!< IRDA Rx DMA Handle parameters */
180 HAL_LockTypeDef Lock
; /*!< Locking object */
182 __IO HAL_IRDA_StateTypeDef gState
; /*!< IRDA state information related to global Handle management
183 and also related to Tx operations.
184 This parameter can be a value of @ref HAL_IRDA_StateTypeDef */
186 __IO HAL_IRDA_StateTypeDef RxState
; /*!< IRDA state information related to Rx operations.
187 This parameter can be a value of @ref HAL_IRDA_StateTypeDef */
189 __IO
uint32_t ErrorCode
; /*!< IRDA Error code */
196 /* Exported constants --------------------------------------------------------*/
197 /** @defgroup IRDA_Exported_Constants IRDA Exported constants
200 /** @defgroup IRDA_Error_Code IRDA Error Code
203 #define HAL_IRDA_ERROR_NONE 0x00000000U /*!< No error */
204 #define HAL_IRDA_ERROR_PE 0x00000001U /*!< Parity error */
205 #define HAL_IRDA_ERROR_NE 0x00000002U /*!< Noise error */
206 #define HAL_IRDA_ERROR_FE 0x00000004U /*!< Frame error */
207 #define HAL_IRDA_ERROR_ORE 0x00000008U /*!< Overrun error */
208 #define HAL_IRDA_ERROR_DMA 0x00000010U /*!< DMA transfer error */
213 /** @defgroup IRDA_Word_Length IRDA Word Length
216 #define IRDA_WORDLENGTH_8B 0x00000000U
217 #define IRDA_WORDLENGTH_9B ((uint32_t)USART_CR1_M)
222 /** @defgroup IRDA_Parity IRDA Parity
225 #define IRDA_PARITY_NONE 0x00000000U
226 #define IRDA_PARITY_EVEN ((uint32_t)USART_CR1_PCE)
227 #define IRDA_PARITY_ODD ((uint32_t)(USART_CR1_PCE | USART_CR1_PS))
232 /** @defgroup IRDA_Transfer_Mode IRDA Transfer Mode
235 #define IRDA_MODE_RX ((uint32_t)USART_CR1_RE)
236 #define IRDA_MODE_TX ((uint32_t)USART_CR1_TE)
237 #define IRDA_MODE_TX_RX ((uint32_t)(USART_CR1_TE |USART_CR1_RE))
242 /** @defgroup IRDA_Low_Power IRDA Low Power
245 #define IRDA_POWERMODE_LOWPOWER ((uint32_t)USART_CR3_IRLP)
246 #define IRDA_POWERMODE_NORMAL 0x00000000U
251 /** @defgroup IRDA_Flags IRDA Flags
252 * Elements values convention: 0xXXXX
253 * - 0xXXXX : Flag mask in the SR register
256 #define IRDA_FLAG_TXE ((uint32_t)USART_SR_TXE)
257 #define IRDA_FLAG_TC ((uint32_t)USART_SR_TC)
258 #define IRDA_FLAG_RXNE ((uint32_t)USART_SR_RXNE)
259 #define IRDA_FLAG_IDLE ((uint32_t)USART_SR_IDLE)
260 #define IRDA_FLAG_ORE ((uint32_t)USART_SR_ORE)
261 #define IRDA_FLAG_NE ((uint32_t)USART_SR_NE)
262 #define IRDA_FLAG_FE ((uint32_t)USART_SR_FE)
263 #define IRDA_FLAG_PE ((uint32_t)USART_SR_PE)
268 /** @defgroup IRDA_Interrupt_definition IRDA Interrupt Definitions
269 * Elements values convention: 0xY000XXXX
270 * - XXXX : Interrupt mask in the XX register
271 * - Y : Interrupt source register (2bits)
277 #define IRDA_IT_PE ((uint32_t)(IRDA_CR1_REG_INDEX << 28U | USART_CR1_PEIE))
278 #define IRDA_IT_TXE ((uint32_t)(IRDA_CR1_REG_INDEX << 28U | USART_CR1_TXEIE))
279 #define IRDA_IT_TC ((uint32_t)(IRDA_CR1_REG_INDEX << 28U | USART_CR1_TCIE))
280 #define IRDA_IT_RXNE ((uint32_t)(IRDA_CR1_REG_INDEX << 28U | USART_CR1_RXNEIE))
281 #define IRDA_IT_IDLE ((uint32_t)(IRDA_CR1_REG_INDEX << 28U | USART_CR1_IDLEIE))
283 #define IRDA_IT_LBD ((uint32_t)(IRDA_CR2_REG_INDEX << 28U | USART_CR2_LBDIE))
285 #define IRDA_IT_CTS ((uint32_t)(IRDA_CR3_REG_INDEX << 28U | USART_CR3_CTSIE))
286 #define IRDA_IT_ERR ((uint32_t)(IRDA_CR3_REG_INDEX << 28U | USART_CR3_EIE))
295 /* Exported macro ------------------------------------------------------------*/
296 /** @defgroup IRDA_Exported_Macros IRDA Exported Macros
300 /** @brief Reset IRDA handle gstate & RxState
301 * @param __HANDLE__: specifies the IRDA Handle.
302 * IRDA Handle selects the USARTx or UARTy peripheral
303 * (USART,UART availability and x,y values depending on device).
305 #define __HAL_IRDA_RESET_HANDLE_STATE(__HANDLE__) do{ \
306 (__HANDLE__)->gState = HAL_IRDA_STATE_RESET; \
307 (__HANDLE__)->RxState = HAL_IRDA_STATE_RESET; \
310 /** @brief Flush the IRDA DR register
311 * @param __HANDLE__: specifies the USART Handle.
312 * IRDA Handle selects the USARTx or UARTy peripheral
313 * (USART,UART availability and x,y values depending on device).
315 #define __HAL_IRDA_FLUSH_DRREGISTER(__HANDLE__) ((__HANDLE__)->Instance->DR)
317 /** @brief Check whether the specified IRDA flag is set or not.
318 * @param __HANDLE__: specifies the IRDA Handle.
319 * IRDA Handle selects the USARTx or UARTy peripheral
320 * (USART,UART availability and x,y values depending on device).
321 * @param __FLAG__: specifies the flag to check.
322 * This parameter can be one of the following values:
323 * @arg IRDA_FLAG_TXE: Transmit data register empty flag
324 * @arg IRDA_FLAG_TC: Transmission Complete flag
325 * @arg IRDA_FLAG_RXNE: Receive data register not empty flag
326 * @arg IRDA_FLAG_IDLE: Idle Line detection flag
327 * @arg IRDA_FLAG_ORE: OverRun Error flag
328 * @arg IRDA_FLAG_NE: Noise Error flag
329 * @arg IRDA_FLAG_FE: Framing Error flag
330 * @arg IRDA_FLAG_PE: Parity Error flag
331 * @retval The new state of __FLAG__ (TRUE or FALSE).
333 #define __HAL_IRDA_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR & (__FLAG__)) == (__FLAG__))
335 /** @brief Clear the specified IRDA pending flag.
336 * @param __HANDLE__: specifies the IRDA Handle.
337 * IRDA Handle selects the USARTx or UARTy peripheral
338 * (USART,UART availability and x,y values depending on device).
339 * @param __FLAG__: specifies the flag to check.
340 * This parameter can be any combination of the following values:
341 * @arg IRDA_FLAG_TC: Transmission Complete flag.
342 * @arg IRDA_FLAG_RXNE: Receive data register not empty flag.
344 * @note PE (Parity error), FE (Framing error), NE (Noise error), ORE (OverRun
345 * error) and IDLE (Idle line detected) flags are cleared by software
346 * sequence: a read operation to USART_SR register followed by a read
347 * operation to USART_DR register.
348 * @note RXNE flag can be also cleared by a read to the USART_DR register.
349 * @note TC flag can be also cleared by software sequence: a read operation to
350 * USART_SR register followed by a write operation to USART_DR register.
351 * @note TXE flag is cleared only by a write to the USART_DR register.
354 #define __HAL_IRDA_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->SR = ~(__FLAG__))
356 /** @brief Clear the IRDA PE pending flag.
357 * @param __HANDLE__: specifies the IRDA Handle.
358 * IRDA Handle selects the USARTx or UARTy peripheral
359 * (USART,UART availability and x,y values depending on device).
361 #define __HAL_IRDA_CLEAR_PEFLAG(__HANDLE__) \
363 __IO uint32_t tmpreg = 0x00U; \
364 tmpreg = (__HANDLE__)->Instance->SR; \
365 tmpreg = (__HANDLE__)->Instance->DR; \
369 /** @brief Clear the IRDA FE pending flag.
370 * @param __HANDLE__: specifies the IRDA Handle.
371 * IRDA Handle selects the USARTx or UARTy peripheral
372 * (USART,UART availability and x,y values depending on device).
374 #define __HAL_IRDA_CLEAR_FEFLAG(__HANDLE__) __HAL_IRDA_CLEAR_PEFLAG(__HANDLE__)
376 /** @brief Clear the IRDA NE pending flag.
377 * @param __HANDLE__: specifies the IRDA Handle.
378 * IRDA Handle selects the USARTx or UARTy peripheral
379 * (USART,UART availability and x,y values depending on device).
381 #define __HAL_IRDA_CLEAR_NEFLAG(__HANDLE__) __HAL_IRDA_CLEAR_PEFLAG(__HANDLE__)
383 /** @brief Clear the IRDA ORE pending flag.
384 * @param __HANDLE__: specifies the IRDA Handle.
385 * IRDA Handle selects the USARTx or UARTy peripheral
386 * (USART,UART availability and x,y values depending on device).
388 #define __HAL_IRDA_CLEAR_OREFLAG(__HANDLE__) __HAL_IRDA_CLEAR_PEFLAG(__HANDLE__)
390 /** @brief Clear the IRDA IDLE pending flag.
391 * @param __HANDLE__: specifies the IRDA Handle.
392 * IRDA Handle selects the USARTx or UARTy peripheral
393 * (USART,UART availability and x,y values depending on device).
395 #define __HAL_IRDA_CLEAR_IDLEFLAG(__HANDLE__) __HAL_IRDA_CLEAR_PEFLAG(__HANDLE__)
397 /** @brief Enable the specified IRDA interrupt.
398 * @param __HANDLE__: specifies the IRDA Handle.
399 * IRDA Handle selects the USARTx or UARTy peripheral
400 * (USART,UART availability and x,y values depending on device).
401 * @param __INTERRUPT__: specifies the IRDA interrupt source to enable.
402 * This parameter can be one of the following values:
403 * @arg IRDA_IT_TXE: Transmit Data Register empty interrupt
404 * @arg IRDA_IT_TC: Transmission complete interrupt
405 * @arg IRDA_IT_RXNE: Receive Data register not empty interrupt
406 * @arg IRDA_IT_IDLE: Idle line detection interrupt
407 * @arg IRDA_IT_PE: Parity Error interrupt
408 * @arg IRDA_IT_ERR: Error interrupt(Frame error, noise error, overrun error)
410 #define __HAL_IRDA_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((((__INTERRUPT__) >> 28U) == IRDA_CR1_REG_INDEX)? ((__HANDLE__)->Instance->CR1 |= ((__INTERRUPT__) & IRDA_IT_MASK)): \
411 (((__INTERRUPT__) >> 28U) == IRDA_CR2_REG_INDEX)? ((__HANDLE__)->Instance->CR2 |= ((__INTERRUPT__) & IRDA_IT_MASK)): \
412 ((__HANDLE__)->Instance->CR3 |= ((__INTERRUPT__) & IRDA_IT_MASK)))
413 /** @brief Disable the specified IRDA interrupt.
414 * @param __HANDLE__: specifies the IRDA Handle.
415 * IRDA Handle selects the USARTx or UARTy peripheral
416 * (USART,UART availability and x,y values depending on device).
417 * @param __INTERRUPT__: specifies the IRDA interrupt source to disable.
418 * This parameter can be one of the following values:
419 * @arg IRDA_IT_TXE: Transmit Data Register empty interrupt
420 * @arg IRDA_IT_TC: Transmission complete interrupt
421 * @arg IRDA_IT_RXNE: Receive Data register not empty interrupt
422 * @arg IRDA_IT_IDLE: Idle line detection interrupt
423 * @arg IRDA_IT_PE: Parity Error interrupt
424 * @arg IRDA_IT_ERR: Error interrupt(Frame error, noise error, overrun error)
426 #define __HAL_IRDA_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((((__INTERRUPT__) >> 28U) == IRDA_CR1_REG_INDEX)? ((__HANDLE__)->Instance->CR1 &= ~((__INTERRUPT__) & IRDA_IT_MASK)): \
427 (((__INTERRUPT__) >> 28U) == IRDA_CR2_REG_INDEX)? ((__HANDLE__)->Instance->CR2 &= ~((__INTERRUPT__) & IRDA_IT_MASK)): \
428 ((__HANDLE__)->Instance->CR3 &= ~ ((__INTERRUPT__) & IRDA_IT_MASK)))
430 /** @brief Check whether the specified IRDA interrupt has occurred or not.
431 * @param __HANDLE__: specifies the IRDA Handle.
432 * IRDA Handle selects the USARTx or UARTy peripheral
433 * (USART,UART availability and x,y values depending on device).
434 * @param __IT__: specifies the IRDA interrupt source to check.
435 * This parameter can be one of the following values:
436 * @arg IRDA_IT_TXE: Transmit Data Register empty interrupt
437 * @arg IRDA_IT_TC: Transmission complete interrupt
438 * @arg IRDA_IT_RXNE: Receive Data register not empty interrupt
439 * @arg IRDA_IT_IDLE: Idle line detection interrupt
440 * @arg IRDA_IT_ERR: Error interrupt
441 * @arg IRDA_IT_PE: Parity Error interrupt
442 * @retval The new state of __IT__ (TRUE or FALSE).
444 #define __HAL_IRDA_GET_IT_SOURCE(__HANDLE__, __IT__) (((((__IT__) >> 28U) == IRDA_CR1_REG_INDEX)? (__HANDLE__)->Instance->CR1:(((((uint32_t)(__IT__)) >> 28U) == IRDA_CR2_REG_INDEX)? \
445 (__HANDLE__)->Instance->CR2 : (__HANDLE__)->Instance->CR3)) & (((uint32_t)(__IT__)) & IRDA_IT_MASK))
447 /** @brief Enable UART/USART associated to IRDA Handle
448 * @param __HANDLE__: specifies the IRDA Handle.
449 * IRDA Handle selects the USARTx or UARTy peripheral
450 * (USART,UART availability and x,y values depending on device).
452 #define __HAL_IRDA_ENABLE(__HANDLE__) (SET_BIT((__HANDLE__)->Instance->CR1, USART_CR1_UE))
454 /** @brief Disable UART/USART associated to IRDA Handle
455 * @param __HANDLE__: specifies the IRDA Handle.
456 * IRDA Handle selects the USARTx or UARTy peripheral
457 * (USART,UART availability and x,y values depending on device).
459 #define __HAL_IRDA_DISABLE(__HANDLE__) (CLEAR_BIT((__HANDLE__)->Instance->CR1, USART_CR1_UE))
465 /* Exported functions --------------------------------------------------------*/
466 /** @addtogroup IRDA_Exported_Functions
470 /** @addtogroup IRDA_Exported_Functions_Group1
473 /* Initialization/de-initialization functions **********************************/
474 HAL_StatusTypeDef
HAL_IRDA_Init(IRDA_HandleTypeDef
*hirda
);
475 HAL_StatusTypeDef
HAL_IRDA_DeInit(IRDA_HandleTypeDef
*hirda
);
476 void HAL_IRDA_MspInit(IRDA_HandleTypeDef
*hirda
);
477 void HAL_IRDA_MspDeInit(IRDA_HandleTypeDef
*hirda
);
482 /** @addtogroup IRDA_Exported_Functions_Group2
485 /* IO operation functions *******************************************************/
486 HAL_StatusTypeDef
HAL_IRDA_Transmit(IRDA_HandleTypeDef
*hirda
, uint8_t *pData
, uint16_t Size
, uint32_t Timeout
);
487 HAL_StatusTypeDef
HAL_IRDA_Receive(IRDA_HandleTypeDef
*hirda
, uint8_t *pData
, uint16_t Size
, uint32_t Timeout
);
488 HAL_StatusTypeDef
HAL_IRDA_Transmit_IT(IRDA_HandleTypeDef
*hirda
, uint8_t *pData
, uint16_t Size
);
489 HAL_StatusTypeDef
HAL_IRDA_Receive_IT(IRDA_HandleTypeDef
*hirda
, uint8_t *pData
, uint16_t Size
);
490 HAL_StatusTypeDef
HAL_IRDA_Transmit_DMA(IRDA_HandleTypeDef
*hirda
, uint8_t *pData
, uint16_t Size
);
491 HAL_StatusTypeDef
HAL_IRDA_Receive_DMA(IRDA_HandleTypeDef
*hirda
, uint8_t *pData
, uint16_t Size
);
492 HAL_StatusTypeDef
HAL_IRDA_DMAPause(IRDA_HandleTypeDef
*hirda
);
493 HAL_StatusTypeDef
HAL_IRDA_DMAResume(IRDA_HandleTypeDef
*hirda
);
494 HAL_StatusTypeDef
HAL_IRDA_DMAStop(IRDA_HandleTypeDef
*hirda
);
495 /* Transfer Abort functions */
496 HAL_StatusTypeDef
HAL_IRDA_Abort(IRDA_HandleTypeDef
*hirda
);
497 HAL_StatusTypeDef
HAL_IRDA_AbortTransmit(IRDA_HandleTypeDef
*hirda
);
498 HAL_StatusTypeDef
HAL_IRDA_AbortReceive(IRDA_HandleTypeDef
*hirda
);
499 HAL_StatusTypeDef
HAL_IRDA_Abort_IT(IRDA_HandleTypeDef
*hirda
);
500 HAL_StatusTypeDef
HAL_IRDA_AbortTransmit_IT(IRDA_HandleTypeDef
*hirda
);
501 HAL_StatusTypeDef
HAL_IRDA_AbortReceive_IT(IRDA_HandleTypeDef
*hirda
);
503 void HAL_IRDA_IRQHandler(IRDA_HandleTypeDef
*hirda
);
504 void HAL_IRDA_TxCpltCallback(IRDA_HandleTypeDef
*hirda
);
505 void HAL_IRDA_RxCpltCallback(IRDA_HandleTypeDef
*hirda
);
506 void HAL_IRDA_TxHalfCpltCallback(IRDA_HandleTypeDef
*hirda
);
507 void HAL_IRDA_RxHalfCpltCallback(IRDA_HandleTypeDef
*hirda
);
508 void HAL_IRDA_ErrorCallback(IRDA_HandleTypeDef
*hirda
);
509 void HAL_IRDA_AbortCpltCallback(IRDA_HandleTypeDef
*hirda
);
510 void HAL_IRDA_AbortTransmitCpltCallback(IRDA_HandleTypeDef
*hirda
);
511 void HAL_IRDA_AbortReceiveCpltCallback(IRDA_HandleTypeDef
*hirda
);
516 /** @addtogroup IRDA_Exported_Functions_Group3
519 /* Peripheral State functions **************************************************/
520 HAL_IRDA_StateTypeDef
HAL_IRDA_GetState(IRDA_HandleTypeDef
*hirda
);
521 uint32_t HAL_IRDA_GetError(IRDA_HandleTypeDef
*hirda
);
530 /* Private types -------------------------------------------------------------*/
531 /* Private variables ---------------------------------------------------------*/
532 /* Private constants ---------------------------------------------------------*/
533 /** @defgroup IRDA_Private_Constants IRDA Private Constants
537 /** @brief IRDA interruptions flag mask
540 #define IRDA_IT_MASK 0x0000FFFFU
542 #define IRDA_CR1_REG_INDEX 1U
543 #define IRDA_CR2_REG_INDEX 2U
544 #define IRDA_CR3_REG_INDEX 3U
549 /* Private macros --------------------------------------------------------*/
550 /** @defgroup IRDA_Private_Macros IRDA Private Macros
553 #define IS_IRDA_WORD_LENGTH(LENGTH) (((LENGTH) == IRDA_WORDLENGTH_8B) || \
554 ((LENGTH) == IRDA_WORDLENGTH_9B))
555 #define IS_IRDA_PARITY(PARITY) (((PARITY) == IRDA_PARITY_NONE) || \
556 ((PARITY) == IRDA_PARITY_EVEN) || \
557 ((PARITY) == IRDA_PARITY_ODD))
558 #define IS_IRDA_MODE(MODE) ((((MODE) & 0x0000FFF3U) == 0x00U) && ((MODE) != 0x00000000U))
559 #define IS_IRDA_POWERMODE(MODE) (((MODE) == IRDA_POWERMODE_LOWPOWER) || \
560 ((MODE) == IRDA_POWERMODE_NORMAL))
561 #define IS_IRDA_BAUDRATE(BAUDRATE) ((BAUDRATE) < 115201U)
563 #define IRDA_DIV(_PCLK_, _BAUD_) (((_PCLK_)*25U)/(4U*(_BAUD_)))
564 #define IRDA_DIVMANT(_PCLK_, _BAUD_) (IRDA_DIV((_PCLK_), (_BAUD_))/100U)
565 #define IRDA_DIVFRAQ(_PCLK_, _BAUD_) (((IRDA_DIV((_PCLK_), (_BAUD_)) - (IRDA_DIVMANT((_PCLK_), (_BAUD_)) * 100U)) * 16U + 50U) / 100U)
566 /* UART BRR = mantissa + overflow + fraction
567 = (UART DIVMANT << 4) + (UART DIVFRAQ & 0xF0) + (UART DIVFRAQ & 0x0FU) */
568 #define IRDA_BRR(_PCLK_, _BAUD_) (((IRDA_DIVMANT((_PCLK_), (_BAUD_)) << 4U) + \
569 (IRDA_DIVFRAQ((_PCLK_), (_BAUD_)) & 0xF0U)) + \
570 (IRDA_DIVFRAQ((_PCLK_), (_BAUD_)) & 0x0FU))
576 /* Private functions ---------------------------------------------------------*/
577 /** @defgroup IRDA_Private_Functions IRDA Private Functions
597 #endif /* __STM32F1xx_HAL_IRDA_H */
599 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/