Classes | Macros | Typedefs | Enumerations | Functions
UART_Adapter

Classes

struct  _hal_uart_config
 UART configuration structure. More...
 
struct  _hal_uart_transfer
 UART transfer structure. More...
 

Macros

#define HAL_UART_ADAPTER_LOWPOWER   (0U)
 
#define HAL_UART_HANDLE_SIZE   (4U + HAL_UART_ADAPTER_LOWPOWER * 16U)
 Definition of uart adapter handle size. More...
 
#define HAL_UART_ISR_PRIORITY   (3U)
 
#define HAL_UART_TRANSFER_MODE   (0U)
 Whether enable transactional function of the UART. (0 - disable, 1 - enable) More...
 
#define UART_ADAPTER_NON_BLOCKING_MODE   (0U)
 Enable or disable UART adapter non-blocking mode (1 - enable, 0 - disable) More...
 
#define UART_HANDLE_DEFINE(name)   uint32_t name[((HAL_UART_HANDLE_SIZE + sizeof(uint32_t) - 1U) / sizeof(uint32_t))]
 Defines the uart handle. More...
 

Typedefs

typedef struct _hal_uart_config hal_uart_config_t
 UART configuration structure. More...
 
typedef void * hal_uart_handle_t
 The handle of uart adapter. More...
 
typedef enum _hal_uart_parity_mode hal_uart_parity_mode_t
 UART parity mode. More...
 
typedef enum _hal_uart_status hal_uart_status_t
 UART status. More...
 
typedef enum _hal_uart_stop_bit_count hal_uart_stop_bit_count_t
 UART stop bit count. More...
 
typedef void(* hal_uart_transfer_callback_t) (hal_uart_handle_t handle, hal_uart_status_t status, void *callbackParam)
 UART transfer callback function. More...
 
typedef struct _hal_uart_transfer hal_uart_transfer_t
 UART transfer structure. More...
 

Enumerations

enum  _hal_uart_parity_mode { kHAL_UartParityDisabled = 0x0U, kHAL_UartParityEven = 0x1U, kHAL_UartParityOdd = 0x2U }
 UART parity mode. More...
 
enum  _hal_uart_status {
  kStatus_HAL_UartSuccess = kStatus_Success, kStatus_HAL_UartTxBusy = MAKE_STATUS(kStatusGroup_HAL_UART, 1), kStatus_HAL_UartRxBusy = MAKE_STATUS(kStatusGroup_HAL_UART, 2), kStatus_HAL_UartTxIdle = MAKE_STATUS(kStatusGroup_HAL_UART, 3),
  kStatus_HAL_UartRxIdle = MAKE_STATUS(kStatusGroup_HAL_UART, 4), kStatus_HAL_UartBaudrateNotSupport, kStatus_HAL_UartProtocolError, kStatus_HAL_UartError = MAKE_STATUS(kStatusGroup_HAL_UART, 7)
}
 UART status. More...
 
enum  _hal_uart_stop_bit_count { kHAL_UartOneStopBit = 0U, kHAL_UartTwoStopBit = 1U }
 UART stop bit count. More...
 

Functions

hal_uart_status_t HAL_UartEnterLowpower (hal_uart_handle_t handle)
 Prepares to enter low power consumption. More...
 
hal_uart_status_t HAL_UartExitLowpower (hal_uart_handle_t handle)
 Restores from low power consumption. More...
 

Initialization and deinitialization

hal_uart_status_t HAL_UartInit (hal_uart_handle_t handle, hal_uart_config_t *config)
 Initializes a UART instance with the UART handle and the user configuration structure. More...
 
hal_uart_status_t HAL_UartDeinit (hal_uart_handle_t handle)
 Deinitializes a UART instance. More...
 

Blocking bus Operations

hal_uart_status_t HAL_UartReceiveBlocking (hal_uart_handle_t handle, uint8_t *data, size_t length)
 Reads RX data register using a blocking method. More...
 
hal_uart_status_t HAL_UartSendBlocking (hal_uart_handle_t handle, const uint8_t *data, size_t length)
 Writes to the TX register using a blocking method. More...
 

Detailed Description

Macro Definition Documentation

◆ HAL_UART_ADAPTER_LOWPOWER

#define HAL_UART_ADAPTER_LOWPOWER   (0U)

Definition at line 64 of file uart.h.

◆ HAL_UART_HANDLE_SIZE

#define HAL_UART_HANDLE_SIZE   (4U + HAL_UART_ADAPTER_LOWPOWER * 16U)

Definition of uart adapter handle size.

Definition at line 71 of file uart.h.

◆ HAL_UART_ISR_PRIORITY

#define HAL_UART_ISR_PRIORITY   (3U)

Definition at line 58 of file uart.h.

◆ HAL_UART_TRANSFER_MODE

#define HAL_UART_TRANSFER_MODE   (0U)

Whether enable transactional function of the UART. (0 - disable, 1 - enable)

Definition at line 93 of file uart.h.

◆ UART_ADAPTER_NON_BLOCKING_MODE

#define UART_ADAPTER_NON_BLOCKING_MODE   (0U)

Enable or disable UART adapter non-blocking mode (1 - enable, 0 - disable)

When defined DEBUG_CONSOLE_TRANSFER_NON_BLOCKING and the interrupt of the UART peripheral with setting instance is not routed to interrupt controller directly, the enablement and priority of the peripheral interrupt are not configured by UART adapter. Please configure the interrupt in the application layer. Such as, if the interrupt of UART peripheral routes to INTMUX, please call function INTMUX_EnableInterrupt of INTMUX to enable the interrupt of the instance.

Definition at line 37 of file uart.h.

◆ UART_HANDLE_DEFINE

#define UART_HANDLE_DEFINE (   name)    uint32_t name[((HAL_UART_HANDLE_SIZE + sizeof(uint32_t) - 1U) / sizeof(uint32_t))]

Defines the uart handle.

This macro is used to define a 4 byte aligned uart handle. Then use "(hal_uart_handle_t)name" to get the uart handle.

The macro should be global and could be optional. You could also define uart handle by yourself.

This is an example,

UART_HANDLE_DEFINE(uartHandle);
Parameters
nameThe name string of the uart handle.

Definition at line 89 of file uart.h.

Typedef Documentation

◆ hal_uart_config_t

UART configuration structure.

◆ hal_uart_handle_t

typedef void* hal_uart_handle_t

The handle of uart adapter.

Definition at line 97 of file uart.h.

◆ hal_uart_parity_mode_t

UART parity mode.

◆ hal_uart_status_t

UART status.

◆ hal_uart_stop_bit_count_t

UART stop bit count.

◆ hal_uart_transfer_callback_t

typedef void(* hal_uart_transfer_callback_t) (hal_uart_handle_t handle, hal_uart_status_t status, void *callbackParam)

UART transfer callback function.

Definition at line 146 of file uart.h.

◆ hal_uart_transfer_t

UART transfer structure.

Enumeration Type Documentation

◆ _hal_uart_parity_mode

UART parity mode.

Enumerator
kHAL_UartParityDisabled 

Parity disabled

kHAL_UartParityEven 

Parity even enabled

kHAL_UartParityOdd 

Parity odd enabled

Definition at line 117 of file uart.h.

◆ _hal_uart_status

UART status.

Enumerator
kStatus_HAL_UartSuccess 

Successfully

kStatus_HAL_UartTxBusy 

TX busy

kStatus_HAL_UartRxBusy 

RX busy

kStatus_HAL_UartTxIdle 

HAL UART transmitter is idle.

kStatus_HAL_UartRxIdle 

HAL UART receiver is idle

kStatus_HAL_UartBaudrateNotSupport 

Baudrate is not support in current clock source

kStatus_HAL_UartProtocolError 

Error occurs for Noise, Framing, Parity, etc. For transactional transfer, The up layer needs to abort the transfer and then starts again

kStatus_HAL_UartError 

Error occurs on HAL UART

Definition at line 100 of file uart.h.

◆ _hal_uart_stop_bit_count

UART stop bit count.

Enumerator
kHAL_UartOneStopBit 

One stop bit

kHAL_UartTwoStopBit 

Two stop bits

Definition at line 125 of file uart.h.

Function Documentation

◆ HAL_UartDeinit()

hal_uart_status_t HAL_UartDeinit ( hal_uart_handle_t  handle)

Deinitializes a UART instance.

This function waits for TX complete, disables TX and RX, and disables the UART clock.

Parameters
handleUART handle pointer.
Return values
kStatus_HAL_UartSuccessUART de-initialization succeed

Definition at line 310 of file lpuart_adapter.c.

◆ HAL_UartEnterLowpower()

hal_uart_status_t HAL_UartEnterLowpower ( hal_uart_handle_t  handle)

Prepares to enter low power consumption.

This function is used to prepare to enter low power consumption.

Parameters
handleUART handle pointer.
Return values
kStatus_HAL_UartSuccessSuccessful operation.
kStatus_HAL_UartErrorAn error occurred.

Definition at line 374 of file lpuart_adapter.c.

◆ HAL_UartExitLowpower()

hal_uart_status_t HAL_UartExitLowpower ( hal_uart_handle_t  handle)

Restores from low power consumption.

This function is used to restore from low power consumption.

Parameters
handleUART handle pointer.
Return values
kStatus_HAL_UartSuccessSuccessful operation.
kStatus_HAL_UartErrorAn error occurred.

Definition at line 381 of file lpuart_adapter.c.

◆ HAL_UartInit()

hal_uart_status_t HAL_UartInit ( hal_uart_handle_t  handle,
hal_uart_config_t config 
)

Initializes a UART instance with the UART handle and the user configuration structure.

This function configures the UART module with user-defined settings. The user can configure the configuration structure. The parameter handle is a pointer to point to a memory space of size HAL_UART_HANDLE_SIZE allocated by the caller. Example below shows how to use this API to configure the UART.

UART_HANDLE_DEFINE(g_UartHandle);
config.srcClock_Hz = 48000000;
config.baudRate_Bps = 115200U;
config.stopBitCount = kHAL_UartOneStopBit;
config.enableRx = 1;
config.enableTx = 1;
config.instance = 0;
Parameters
handlePointer to point to a memory space of size HAL_UART_HANDLE_SIZE allocated by the caller. The handle should be 4 byte aligned, because unaligned access doesn't be supported on some devices. You can define the handle in the following two ways: UART_HANDLE_DEFINE(handle); or uint32_t handle[((HAL_UART_HANDLE_SIZE + sizeof(uint32_t) - 1U) / sizeof(uint32_t))];
configPointer to user-defined configuration structure.
Return values
kStatus_HAL_UartBaudrateNotSupportBaudrate is not support in current clock source.
kStatus_HAL_UartSuccessUART initialization succeed

Definition at line 226 of file lpuart_adapter.c.

◆ HAL_UartReceiveBlocking()

hal_uart_status_t HAL_UartReceiveBlocking ( hal_uart_handle_t  handle,
uint8_t *  data,
size_t  length 
)

Reads RX data register using a blocking method.

This function polls the RX register, waits for the RX register to be full or for RX FIFO to have data, and reads data from the RX register.

Note
The function HAL_UartReceiveBlocking and the function HAL_UartTransferReceiveNonBlocking cannot be used at the same time. And, the function HAL_UartTransferAbortReceive cannot be used to abort the transmission of this function.
Parameters
handleUART handle pointer.
dataStart address of the buffer to store the received data.
lengthSize of the buffer.
Return values
kStatus_HAL_UartErrorAn error occurred while receiving data.
kStatus_HAL_UartParityErrorA parity error occurred while receiving data.
kStatus_HAL_UartSuccessSuccessfully received all data.

Definition at line 331 of file lpuart_adapter.c.

◆ HAL_UartSendBlocking()

hal_uart_status_t HAL_UartSendBlocking ( hal_uart_handle_t  handle,
const uint8_t *  data,
size_t  length 
)

Writes to the TX register using a blocking method.

This function polls the TX register, waits for the TX register to be empty or for the TX FIFO to have room and writes data to the TX buffer.

Note
The function HAL_UartSendBlocking and the function HAL_UartTransferSendNonBlocking cannot be used at the same time. And, the function HAL_UartTransferAbortSend cannot be used to abort the transmission of this function.
Parameters
handleUART handle pointer.
dataStart address of the data to write.
lengthSize of the data to write.
Return values
kStatus_HAL_UartSuccessSuccessfully sent all data.

Definition at line 353 of file lpuart_adapter.c.

HAL_UartInit
hal_uart_status_t HAL_UartInit(hal_uart_handle_t handle, hal_uart_config_t *config)
Initializes a UART instance with the UART handle and the user configuration structure.
Definition: lpuart_adapter.c:226
hal_uart_handle_t
void * hal_uart_handle_t
The handle of uart adapter.
Definition: uart.h:97
_hal_uart_config
UART configuration structure.
Definition: uart.h:132
kHAL_UartParityDisabled
@ kHAL_UartParityDisabled
Definition: uart.h:119
UART_HANDLE_DEFINE
#define UART_HANDLE_DEFINE(name)
Defines the uart handle.
Definition: uart.h:89
kHAL_UartOneStopBit
@ kHAL_UartOneStopBit
Definition: uart.h:127
config
static sai_transceiver_t config
Definition: imxrt1050/imxrt1050-evkb/source/pv_audio_rec.c:75


picovoice_driver
Author(s):
autogenerated on Fri Apr 1 2022 02:15:09