Classes | Macros | Functions
CHIP: LPC11xx UART driver

Classes

struct  LPC_USART_T
 USART register block structure. More...
 

Macros

#define UART1_IER_BITMASK   (0x30F)
 
#define UART1_LSR_BITMASK   (0x1FF)
 
#define UART2_IER_BITMASK   (0x38F)
 
#define UART_ACR_ABEOINT_CLR   (1 << 8)
 
#define UART_ACR_ABTOINT_CLR   (1 << 9)
 
#define UART_ACR_AUTO_RESTART   (1 << 2)
 
#define UART_ACR_BITMASK   (0x307)
 
#define UART_ACR_MODE   (1 << 1)
 
#define UART_ACR_START   (1 << 0)
 Macro defines for UART Auto baudrate control register. More...
 
#define UART_DLL_MASKBIT   (0xFF)
 
#define UART_DLM_MASKBIT   (0xFF)
 
#define UART_FCR_BITMASK   (0xCF)
 
#define UART_FCR_DMAMODE_SEL   (1 << 3)
 
#define UART_FCR_FIFO_EN   (1 << 0)
 Macro defines for UART FIFO Control Register. More...
 
#define UART_FCR_RX_RS   (1 << 1)
 
#define UART_FCR_TRG_LEV0   (0)
 
#define UART_FCR_TRG_LEV1   (1 << 6)
 
#define UART_FCR_TRG_LEV2   (2 << 6)
 
#define UART_FCR_TRG_LEV3   (3 << 6)
 
#define UART_FCR_TX_RS   (1 << 2)
 
#define UART_FDR_BITMASK   (0xFF)
 
#define UART_FDR_DIVADDVAL(n)   (n & 0x0F)
 Macro defines for UART Fractional Divider Register. More...
 
#define UART_FDR_MULVAL(n)   ((n << 4) & 0xF0)
 
#define UART_HDEN_HDEN   ((1 << 0))
 Macro defines for UART half duplex register - ???? More...
 
#define UART_ICR_BITMASK   (0x3F)
 
#define UART_ICR_FIXPULSE_EN   (1 << 2)
 
#define UART_ICR_IRDAEN   (1 << 0)
 Macro defines for UART IrDA Control Register - valid for 11xx, 17xx/40xx UART0/2/3, 18xx/43xx UART3 only. More...
 
#define UART_ICR_IRDAINV   (1 << 1)
 
#define UART_ICR_PULSEDIV(n)   ((n & 0x07) << 3)
 
#define UART_IER_ABEOINT   (1 << 8)
 
#define UART_IER_ABTOINT   (1 << 9)
 
#define UART_IER_BITMASK   (0x307)
 
#define UART_IER_CTSINT   (1 << 7)
 
#define UART_IER_MSINT   (1 << 3)
 
#define UART_IER_RBRINT   (1 << 0)
 Macro defines for UART Interrupt Enable Register. More...
 
#define UART_IER_RLSINT   (1 << 2)
 
#define UART_IER_THREINT   (1 << 1)
 
#define UART_IIR_ABEO_INT   (1 << 8)
 
#define UART_IIR_ABTO_INT   (1 << 9)
 
#define UART_IIR_BITMASK   (0x3CF)
 
#define UART_IIR_FIFO_EN   (3 << 6)
 
#define UART_IIR_INTID_CTI   (6 << 1)
 
#define UART_IIR_INTID_MASK   (7 << 1)
 
#define UART_IIR_INTID_MODEM   (0 << 1)
 
#define UART_IIR_INTID_RDA   (2 << 1)
 
#define UART_IIR_INTID_RLS   (3 << 1)
 
#define UART_IIR_INTID_THRE   (1 << 1)
 
#define UART_IIR_INTSTAT_PEND   (1 << 0)
 Macro defines for UART Interrupt Identification Register. More...
 
#define UART_LCR_BITMASK   (0xFF)
 
#define UART_LCR_BREAK_EN   (1 << 6)
 
#define UART_LCR_DLAB_EN   (1 << 7)
 
#define UART_LCR_PARITY_DIS   (0 << 3)
 
#define UART_LCR_PARITY_EN   (1 << 3)
 
#define UART_LCR_PARITY_EVEN   (1 << 4)
 
#define UART_LCR_PARITY_F_0   (3 << 4)
 
#define UART_LCR_PARITY_F_1   (2 << 4)
 
#define UART_LCR_PARITY_ODD   (0 << 4)
 
#define UART_LCR_SBS_1BIT   (0 << 2)
 
#define UART_LCR_SBS_2BIT   (1 << 2)
 
#define UART_LCR_SBS_MASK   (1 << 2)
 
#define UART_LCR_WLEN5   (0 << 0)
 
#define UART_LCR_WLEN6   (1 << 0)
 
#define UART_LCR_WLEN7   (2 << 0)
 
#define UART_LCR_WLEN8   (3 << 0)
 
#define UART_LCR_WLEN_MASK   (3 << 0)
 Macro defines for UART Line Control Register. More...
 
#define UART_LOAD_DLL(div)   ((div) & 0xFF)
 Macro defines for UART Divisor Latch LSB register. More...
 
#define UART_LOAD_DLM(div)   (((div) >> 8) & 0xFF)
 Macro defines for UART Divisor Latch MSB register. More...
 
#define UART_LSR_BI   (1 << 4)
 
#define UART_LSR_BITMASK   (0xFF)
 
#define UART_LSR_FE   (1 << 3)
 
#define UART_LSR_OE   (1 << 1)
 
#define UART_LSR_PE   (1 << 2)
 
#define UART_LSR_RDR   (1 << 0)
 Macro defines for UART Line Status Register. More...
 
#define UART_LSR_RXFE   (1 << 7)
 
#define UART_LSR_TEMT   (1 << 6)
 
#define UART_LSR_THRE   (1 << 5)
 
#define UART_LSR_TXFE   (1 << 8)
 
#define UART_MCR_AUTO_CTS_EN   (1 << 7)
 
#define UART_MCR_AUTO_RTS_EN   (1 << 6)
 
#define UART_MCR_BITMASK   (0xD3)
 
#define UART_MCR_DTR_CTRL   (1 << 0)
 Macro defines for UART Modem Control Register. More...
 
#define UART_MCR_LOOPB_EN   (1 << 4)
 
#define UART_MCR_RTS_CTRL   (1 << 1)
 
#define UART_MSR_BITMASK   (0xFF)
 
#define UART_MSR_CTS   (1 << 4)
 
#define UART_MSR_DCD   (1 << 7)
 
#define UART_MSR_DELTA_CTS   (1 << 0)
 Macro defines for UART Modem Status Register. More...
 
#define UART_MSR_DELTA_DCD   (1 << 3)
 
#define UART_MSR_DELTA_DSR   (1 << 1)
 
#define UART_MSR_DSR   (1 << 5)
 
#define UART_MSR_LO2HI_RI   (1 << 2)
 
#define UART_MSR_RI   (1 << 6)
 
#define UART_RBR_MASKBIT   (0xFF)
 Macro defines for UART Receive Buffer register. More...
 
#define UART_RS485CTRL_AADEN   (1 << 2)
 
#define UART_RS485CTRL_BITMASK   (0x3F)
 
#define UART_RS485CTRL_DCTRL_EN   (1 << 4)
 
#define UART_RS485CTRL_NMM_EN   (1 << 0)
 Macro defines for UART RS485 Control register. More...
 
#define UART_RS485CTRL_OINV_1   (1 << 5)
 
#define UART_RS485CTRL_RX_DIS   (1 << 1)
 
#define UART_RS485CTRL_SEL_DTR   (1 << 3)
 
#define UART_SCICTRL_GUARDTIME(n)   ((n & 0xFF) << 8)
 
#define UART_SCICTRL_NACKDIS   (1 << 1)
 
#define UART_SCICTRL_PROTSEL_T1   (1 << 2)
 
#define UART_SCICTRL_SCIEN   (1 << 0)
 Macro defines for UART Smart card interface Control Register - valid for 11xx, 18xx/43xx UART0/2/3 only. More...
 
#define UART_SCICTRL_TXRETRY(n)   ((n & 0x07) << 5)
 
#define UART_SYNCCTRL_CCCLR   (1 << 6)
 
#define UART_SYNCCTRL_CSCEN   (1 << 4)
 
#define UART_SYNCCTRL_CSRC_MASTER   (1 << 1)
 
#define UART_SYNCCTRL_FES   (1 << 2)
 
#define UART_SYNCCTRL_STARTSTOPDISABLE   (1 << 5)
 
#define UART_SYNCCTRL_SYNC   (1 << 0)
 Macro defines for UART Synchronous Control Register - 11xx, 18xx/43xx UART0/2/3 only. More...
 
#define UART_SYNCCTRL_TSBYPASS   (1 << 3)
 
#define UART_TER1_TXEN   (1 << 7)
 Macro defines for UART Tx Enable Register. More...
 
#define UART_TER2_TXEN   (1 << 0)
 
#define UART_TX_FIFO_SIZE   (16)
 

Functions

STATIC INLINE void Chip_UART_ClearAutoBaudReg (LPC_USART_T *pUART, uint32_t acr)
 Clear autobaud register options. More...
 
STATIC INLINE void Chip_UART_ClearModemControl (LPC_USART_T *pUART, uint32_t mcr)
 Clear modem control register/status. More...
 
STATIC INLINE void Chip_UART_ClearRS485Flags (LPC_USART_T *pUART, uint32_t ctrl)
 Clear RS485 control register options. More...
 
STATIC INLINE void Chip_UART_ConfigData (LPC_USART_T *pUART, uint32_t config)
 Configure data width, parity and stop bits. More...
 
void Chip_UART_DeInit (LPC_USART_T *pUART)
 De-initializes the pUART peripheral. More...
 
STATIC INLINE void Chip_UART_DisableDivisorAccess (LPC_USART_T *pUART)
 Disable access to Divisor Latches. More...
 
STATIC INLINE void Chip_UART_EnableDivisorAccess (LPC_USART_T *pUART)
 Enable access to Divisor Latches. More...
 
STATIC INLINE uint32_t Chip_UART_GetIntsEnabled (LPC_USART_T *pUART)
 Returns UART interrupts that are enabled. More...
 
STATIC INLINE uint8_t Chip_UART_GetRS485Addr (LPC_USART_T *pUART)
 Read RS485 address match value. More...
 
STATIC INLINE uint8_t Chip_UART_GetRS485Delay (LPC_USART_T *pUART)
 Read RS485 direction control (RTS or DTR) delay value. More...
 
void Chip_UART_Init (LPC_USART_T *pUART)
 Initializes the pUART peripheral. More...
 
STATIC INLINE void Chip_UART_IntDisable (LPC_USART_T *pUART, uint32_t intMask)
 Disable UART interrupts. More...
 
STATIC INLINE void Chip_UART_IntEnable (LPC_USART_T *pUART, uint32_t intMask)
 Enable UART interrupts. More...
 
void Chip_UART_IRQRBHandler (LPC_USART_T *pUART, RINGBUFF_T *pRXRB, RINGBUFF_T *pTXRB)
 UART receive/transmit interrupt handler for ring buffers. More...
 
int Chip_UART_Read (LPC_USART_T *pUART, void *data, int numBytes)
 Read data through the UART peripheral (non-blocking) More...
 
int Chip_UART_ReadBlocking (LPC_USART_T *pUART, void *data, int numBytes)
 Read data through the UART peripheral (blocking) More...
 
STATIC INLINE uint8_t Chip_UART_ReadByte (LPC_USART_T *pUART)
 Read a single byte data from the UART peripheral. More...
 
STATIC INLINE uint32_t Chip_UART_ReadIntIDReg (LPC_USART_T *pUART)
 Read the Interrupt Identification Register (IIR) More...
 
STATIC INLINE uint32_t Chip_UART_ReadLineStatus (LPC_USART_T *pUART)
 Return Line Status register/status (LSR) More...
 
STATIC INLINE uint32_t Chip_UART_ReadModemControl (LPC_USART_T *pUART)
 Return modem control register/status. More...
 
STATIC INLINE uint32_t Chip_UART_ReadModemStatus (LPC_USART_T *pUART)
 Return Modem Status register/status (MSR) More...
 
int Chip_UART_ReadRB (LPC_USART_T *pUART, RINGBUFF_T *pRB, void *data, int bytes)
 Copy data from a receive ring buffer. More...
 
STATIC INLINE uint8_t Chip_UART_ReadScratch (LPC_USART_T *pUART)
 Returns current byte value in the scratchpad register. More...
 
void Chip_UART_RXIntHandlerRB (LPC_USART_T *pUART, RINGBUFF_T *pRB)
 UART receive-only interrupt handler for ring buffers. More...
 
int Chip_UART_Send (LPC_USART_T *pUART, const void *data, int numBytes)
 Transmit a byte array through the UART peripheral (non-blocking) More...
 
int Chip_UART_SendBlocking (LPC_USART_T *pUART, const void *data, int numBytes)
 Transmit a byte array through the UART peripheral (blocking) More...
 
STATIC INLINE void Chip_UART_SendByte (LPC_USART_T *pUART, uint8_t data)
 Transmit a single data byte through the UART peripheral. More...
 
uint32_t Chip_UART_SendRB (LPC_USART_T *pUART, RINGBUFF_T *pRB, const void *data, int bytes)
 Populate a transmit ring buffer and start UART transmit. More...
 
STATIC INLINE void Chip_UART_SetAutoBaudReg (LPC_USART_T *pUART, uint32_t acr)
 Set autobaud register options. More...
 
uint32_t Chip_UART_SetBaud (LPC_USART_T *pUART, uint32_t baudrate)
 Sets best dividers to get a target bit rate (without fractional divider) More...
 
uint32_t Chip_UART_SetBaudFDR (LPC_USART_T *pUART, uint32_t baudrate)
 Sets best dividers to get a target bit rate (with fractional divider) More...
 
STATIC INLINE void Chip_UART_SetDivisorLatches (LPC_USART_T *pUART, uint8_t dll, uint8_t dlm)
 Set LSB and MSB divisor latch registers. More...
 
STATIC INLINE void Chip_UART_SetModemControl (LPC_USART_T *pUART, uint32_t mcr)
 Set modem control register/status. More...
 
STATIC INLINE void Chip_UART_SetRS485Addr (LPC_USART_T *pUART, uint8_t addr)
 Set RS485 address match value. More...
 
STATIC INLINE void Chip_UART_SetRS485Delay (LPC_USART_T *pUART, uint8_t dly)
 Set RS485 direction control (RTS or DTR) delay value. More...
 
STATIC INLINE void Chip_UART_SetRS485Flags (LPC_USART_T *pUART, uint32_t ctrl)
 Set RS485 control register options. More...
 
STATIC INLINE void Chip_UART_SetScratch (LPC_USART_T *pUART, uint8_t data)
 Write a byte to the scratchpad register. More...
 
STATIC INLINE void Chip_UART_SetupFIFOS (LPC_USART_T *pUART, uint32_t fcr)
 Setup the UART FIFOs. More...
 
STATIC INLINE void Chip_UART_TXDisable (LPC_USART_T *pUART)
 Disable transmission on UART TxD pin. More...
 
STATIC INLINE void Chip_UART_TXEnable (LPC_USART_T *pUART)
 Enable transmission on UART TxD pin. More...
 
void Chip_UART_TXIntHandlerRB (LPC_USART_T *pUART, RINGBUFF_T *pRB)
 UART transmit-only interrupt handler for ring buffers. More...
 

Detailed Description

Macro Definition Documentation

◆ UART1_IER_BITMASK

#define UART1_IER_BITMASK   (0x30F)

UART1 interrupt enable register bit mask - valid for 11xx only

Definition at line 123 of file uart_11xx.h.

◆ UART1_LSR_BITMASK

#define UART1_LSR_BITMASK   (0x1FF)

UART1 Line status bit mask - valid for 11xx, 18xx/43xx UART0/2/3 only

Definition at line 209 of file uart_11xx.h.

◆ UART2_IER_BITMASK

#define UART2_IER_BITMASK   (0x38F)

UART2 interrupt enable register bit mask - valid for 17xx/40xx UART1, 18xx/43xx UART1 only

Definition at line 124 of file uart_11xx.h.

◆ UART_ACR_ABEOINT_CLR

#define UART_ACR_ABEOINT_CLR   (1 << 8)

UART End of auto-baud interrupt clear

Definition at line 230 of file uart_11xx.h.

◆ UART_ACR_ABTOINT_CLR

#define UART_ACR_ABTOINT_CLR   (1 << 9)

UART Auto-baud time-out interrupt clear

Definition at line 231 of file uart_11xx.h.

◆ UART_ACR_AUTO_RESTART

#define UART_ACR_AUTO_RESTART   (1 << 2)

UART Auto baudrate restart

Definition at line 229 of file uart_11xx.h.

◆ UART_ACR_BITMASK

#define UART_ACR_BITMASK   (0x307)

UART Auto Baudrate register bit mask

Definition at line 232 of file uart_11xx.h.

◆ UART_ACR_MODE

#define UART_ACR_MODE   (1 << 1)

UART Auto baudrate Mode 1

Definition at line 228 of file uart_11xx.h.

◆ UART_ACR_START

#define UART_ACR_START   (1 << 0)

Macro defines for UART Auto baudrate control register.

UART Auto-baud start

Definition at line 227 of file uart_11xx.h.

◆ UART_DLL_MASKBIT

#define UART_DLL_MASKBIT   (0xFF)

Divisor latch LSB bit mask

Definition at line 104 of file uart_11xx.h.

◆ UART_DLM_MASKBIT

#define UART_DLM_MASKBIT   (0xFF)

Divisor latch MSB bit mask

Definition at line 110 of file uart_11xx.h.

◆ UART_FCR_BITMASK

#define UART_FCR_BITMASK   (0xCF)

UART FIFO control bit mask

Definition at line 150 of file uart_11xx.h.

◆ UART_FCR_DMAMODE_SEL

#define UART_FCR_DMAMODE_SEL   (1 << 3)

UART DMA mode selection - valid for 17xx/40xx, 18xx/43xx only

Definition at line 149 of file uart_11xx.h.

◆ UART_FCR_FIFO_EN

#define UART_FCR_FIFO_EN   (1 << 0)

Macro defines for UART FIFO Control Register.

UART FIFO enable

Definition at line 146 of file uart_11xx.h.

◆ UART_FCR_RX_RS

#define UART_FCR_RX_RS   (1 << 1)

UART RX FIFO reset

Definition at line 147 of file uart_11xx.h.

◆ UART_FCR_TRG_LEV0

#define UART_FCR_TRG_LEV0   (0)

UART FIFO trigger level 0: 1 character

Definition at line 155 of file uart_11xx.h.

◆ UART_FCR_TRG_LEV1

#define UART_FCR_TRG_LEV1   (1 << 6)

UART FIFO trigger level 1: 4 character

Definition at line 156 of file uart_11xx.h.

◆ UART_FCR_TRG_LEV2

#define UART_FCR_TRG_LEV2   (2 << 6)

UART FIFO trigger level 2: 8 character

Definition at line 157 of file uart_11xx.h.

◆ UART_FCR_TRG_LEV3

#define UART_FCR_TRG_LEV3   (3 << 6)

UART FIFO trigger level 3: 14 character

Definition at line 158 of file uart_11xx.h.

◆ UART_FCR_TX_RS

#define UART_FCR_TX_RS   (1 << 2)

UART TX FIFO reset

Definition at line 148 of file uart_11xx.h.

◆ UART_FDR_BITMASK

#define UART_FDR_BITMASK   (0xFF)

UART Fractional Divider register bit mask

Definition at line 276 of file uart_11xx.h.

◆ UART_FDR_DIVADDVAL

#define UART_FDR_DIVADDVAL (   n)    (n & 0x0F)

Macro defines for UART Fractional Divider Register.

Baud-rate generation pre-scaler divisor

Definition at line 274 of file uart_11xx.h.

◆ UART_FDR_MULVAL

#define UART_FDR_MULVAL (   n)    ((n << 4) & 0xF0)

Baud-rate pre-scaler multiplier value

Definition at line 275 of file uart_11xx.h.

◆ UART_HDEN_HDEN

#define UART_HDEN_HDEN   ((1 << 0))

Macro defines for UART half duplex register - ????

enable half-duplex mode

Definition at line 260 of file uart_11xx.h.

◆ UART_ICR_BITMASK

#define UART_ICR_BITMASK   (0x3F)

UART IRDA bit mask

Definition at line 255 of file uart_11xx.h.

◆ UART_ICR_FIXPULSE_EN

#define UART_ICR_FIXPULSE_EN   (1 << 2)

IrDA fixed pulse width mode

Definition at line 253 of file uart_11xx.h.

◆ UART_ICR_IRDAEN

#define UART_ICR_IRDAEN   (1 << 0)

Macro defines for UART IrDA Control Register - valid for 11xx, 17xx/40xx UART0/2/3, 18xx/43xx UART3 only.

IrDA mode enable

Definition at line 251 of file uart_11xx.h.

◆ UART_ICR_IRDAINV

#define UART_ICR_IRDAINV   (1 << 1)

IrDA serial input inverted

Definition at line 252 of file uart_11xx.h.

◆ UART_ICR_PULSEDIV

#define UART_ICR_PULSEDIV (   n)    ((n & 0x07) << 3)

PulseDiv - Configures the pulse when FixPulseEn = 1

Definition at line 254 of file uart_11xx.h.

◆ UART_IER_ABEOINT

#define UART_IER_ABEOINT   (1 << 8)

Enables the end of auto-baud interrupt

Definition at line 120 of file uart_11xx.h.

◆ UART_IER_ABTOINT

#define UART_IER_ABTOINT   (1 << 9)

Enables the auto-baud time-out interrupt

Definition at line 121 of file uart_11xx.h.

◆ UART_IER_BITMASK

#define UART_IER_BITMASK   (0x307)

UART interrupt enable register bit mask - valid for 13xx, 17xx/40xx UART0/2/3, 18xx/43xx UART0/2/3 only

Definition at line 122 of file uart_11xx.h.

◆ UART_IER_CTSINT

#define UART_IER_CTSINT   (1 << 7)

CTS signal transition interrupt enable - valid for 17xx/40xx UART1, 18xx/43xx UART1 only

Definition at line 119 of file uart_11xx.h.

◆ UART_IER_MSINT

#define UART_IER_MSINT   (1 << 3)

Modem status interrupt enable - valid for 11xx, 17xx/40xx UART1, 18xx/43xx UART1 only

Definition at line 118 of file uart_11xx.h.

◆ UART_IER_RBRINT

#define UART_IER_RBRINT   (1 << 0)

Macro defines for UART Interrupt Enable Register.

RBR Interrupt enable

Definition at line 115 of file uart_11xx.h.

◆ UART_IER_RLSINT

#define UART_IER_RLSINT   (1 << 2)

RX line status interrupt enable

Definition at line 117 of file uart_11xx.h.

◆ UART_IER_THREINT

#define UART_IER_THREINT   (1 << 1)

THR Interrupt enable

Definition at line 116 of file uart_11xx.h.

◆ UART_IIR_ABEO_INT

#define UART_IIR_ABEO_INT   (1 << 8)

End of auto-baud interrupt

Definition at line 131 of file uart_11xx.h.

◆ UART_IIR_ABTO_INT

#define UART_IIR_ABTO_INT   (1 << 9)

Auto-baud time-out interrupt

Definition at line 132 of file uart_11xx.h.

◆ UART_IIR_BITMASK

#define UART_IIR_BITMASK   (0x3CF)

UART interrupt identification register bit mask

Definition at line 133 of file uart_11xx.h.

◆ UART_IIR_FIFO_EN

#define UART_IIR_FIFO_EN   (3 << 6)

These bits are equivalent to FCR[0]

Definition at line 130 of file uart_11xx.h.

◆ UART_IIR_INTID_CTI

#define UART_IIR_INTID_CTI   (6 << 1)

Interrupt identification: Character time-out indicator interrupt

Definition at line 139 of file uart_11xx.h.

◆ UART_IIR_INTID_MASK

#define UART_IIR_INTID_MASK   (7 << 1)

Interrupt identification: Interrupt ID mask

Definition at line 136 of file uart_11xx.h.

◆ UART_IIR_INTID_MODEM

#define UART_IIR_INTID_MODEM   (0 << 1)

Interrupt identification: Modem interrupt

Definition at line 141 of file uart_11xx.h.

◆ UART_IIR_INTID_RDA

#define UART_IIR_INTID_RDA   (2 << 1)

Interrupt identification: Receive data available interrupt

Definition at line 138 of file uart_11xx.h.

◆ UART_IIR_INTID_RLS

#define UART_IIR_INTID_RLS   (3 << 1)

Interrupt identification: Receive line interrupt

Definition at line 137 of file uart_11xx.h.

◆ UART_IIR_INTID_THRE

#define UART_IIR_INTID_THRE   (1 << 1)

Interrupt identification: THRE interrupt

Definition at line 140 of file uart_11xx.h.

◆ UART_IIR_INTSTAT_PEND

#define UART_IIR_INTSTAT_PEND   (1 << 0)

Macro defines for UART Interrupt Identification Register.

Interrupt pending status - Active low

Definition at line 129 of file uart_11xx.h.

◆ UART_LCR_BITMASK

#define UART_LCR_BITMASK   (0xFF)

UART line control bit mask

Definition at line 184 of file uart_11xx.h.

◆ UART_LCR_BREAK_EN

#define UART_LCR_BREAK_EN   (1 << 6)

UART Break transmission enable

Definition at line 182 of file uart_11xx.h.

◆ UART_LCR_DLAB_EN

#define UART_LCR_DLAB_EN   (1 << 7)

UART Divisor Latches Access bit enable

Definition at line 183 of file uart_11xx.h.

◆ UART_LCR_PARITY_DIS

#define UART_LCR_PARITY_DIS   (0 << 3)

UART Parity Disable

Definition at line 177 of file uart_11xx.h.

◆ UART_LCR_PARITY_EN

#define UART_LCR_PARITY_EN   (1 << 3)

UART Parity Enable

Definition at line 176 of file uart_11xx.h.

◆ UART_LCR_PARITY_EVEN

#define UART_LCR_PARITY_EVEN   (1 << 4)

UART Parity select: Even parity

Definition at line 179 of file uart_11xx.h.

◆ UART_LCR_PARITY_F_0

#define UART_LCR_PARITY_F_0   (3 << 4)

UART Parity select: Forced 0 stick parity

Definition at line 181 of file uart_11xx.h.

◆ UART_LCR_PARITY_F_1

#define UART_LCR_PARITY_F_1   (2 << 4)

UART Parity select: Forced 1 stick parity

Definition at line 180 of file uart_11xx.h.

◆ UART_LCR_PARITY_ODD

#define UART_LCR_PARITY_ODD   (0 << 4)

UART Parity select: Odd parity

Definition at line 178 of file uart_11xx.h.

◆ UART_LCR_SBS_1BIT

#define UART_LCR_SBS_1BIT   (0 << 2)

UART stop bit select: 1 stop bit

Definition at line 172 of file uart_11xx.h.

◆ UART_LCR_SBS_2BIT

#define UART_LCR_SBS_2BIT   (1 << 2)

UART stop bit select: 2 stop bits (in 5 bit data mode, 1.5 stop bits)

Definition at line 173 of file uart_11xx.h.

◆ UART_LCR_SBS_MASK

#define UART_LCR_SBS_MASK   (1 << 2)

UART stop bit select: bit mask

Definition at line 171 of file uart_11xx.h.

◆ UART_LCR_WLEN5

#define UART_LCR_WLEN5   (0 << 0)

UART word length select: 5 bit data mode

Definition at line 165 of file uart_11xx.h.

◆ UART_LCR_WLEN6

#define UART_LCR_WLEN6   (1 << 0)

UART word length select: 6 bit data mode

Definition at line 166 of file uart_11xx.h.

◆ UART_LCR_WLEN7

#define UART_LCR_WLEN7   (2 << 0)

UART word length select: 7 bit data mode

Definition at line 167 of file uart_11xx.h.

◆ UART_LCR_WLEN8

#define UART_LCR_WLEN8   (3 << 0)

UART word length select: 8 bit data mode

Definition at line 168 of file uart_11xx.h.

◆ UART_LCR_WLEN_MASK

#define UART_LCR_WLEN_MASK   (3 << 0)

Macro defines for UART Line Control Register.

UART word length select bit mask

Definition at line 164 of file uart_11xx.h.

◆ UART_LOAD_DLL

#define UART_LOAD_DLL (   div)    ((div) & 0xFF)

Macro defines for UART Divisor Latch LSB register.

Macro for loading LSB of divisor

Definition at line 103 of file uart_11xx.h.

◆ UART_LOAD_DLM

#define UART_LOAD_DLM (   div)    (((div) >> 8) & 0xFF)

Macro defines for UART Divisor Latch MSB register.

Macro for loading MSB of divisors

Definition at line 109 of file uart_11xx.h.

◆ UART_LSR_BI

#define UART_LSR_BI   (1 << 4)

Line status: Break interrupt

Definition at line 203 of file uart_11xx.h.

◆ UART_LSR_BITMASK

#define UART_LSR_BITMASK   (0xFF)

UART Line status bit mask

Definition at line 208 of file uart_11xx.h.

◆ UART_LSR_FE

#define UART_LSR_FE   (1 << 3)

Line status: Framing error

Definition at line 202 of file uart_11xx.h.

◆ UART_LSR_OE

#define UART_LSR_OE   (1 << 1)

Line status: Overrun error

Definition at line 200 of file uart_11xx.h.

◆ UART_LSR_PE

#define UART_LSR_PE   (1 << 2)

Line status: Parity error

Definition at line 201 of file uart_11xx.h.

◆ UART_LSR_RDR

#define UART_LSR_RDR   (1 << 0)

Macro defines for UART Line Status Register.

Line status: Receive data ready

Definition at line 199 of file uart_11xx.h.

◆ UART_LSR_RXFE

#define UART_LSR_RXFE   (1 << 7)

Line status: Error in RX FIFO

Definition at line 206 of file uart_11xx.h.

◆ UART_LSR_TEMT

#define UART_LSR_TEMT   (1 << 6)

Line status: Transmitter empty

Definition at line 205 of file uart_11xx.h.

◆ UART_LSR_THRE

#define UART_LSR_THRE   (1 << 5)

Line status: Transmit holding register empty

Definition at line 204 of file uart_11xx.h.

◆ UART_LSR_TXFE

#define UART_LSR_TXFE   (1 << 8)

Line status: Error in RX FIFO

Definition at line 207 of file uart_11xx.h.

◆ UART_MCR_AUTO_CTS_EN

#define UART_MCR_AUTO_CTS_EN   (1 << 7)

Enable Auto CTS flow-control

Definition at line 193 of file uart_11xx.h.

◆ UART_MCR_AUTO_RTS_EN

#define UART_MCR_AUTO_RTS_EN   (1 << 6)

Enable Auto RTS flow-control

Definition at line 192 of file uart_11xx.h.

◆ UART_MCR_BITMASK

#define UART_MCR_BITMASK   (0xD3)

UART bit mask value

Definition at line 194 of file uart_11xx.h.

◆ UART_MCR_DTR_CTRL

#define UART_MCR_DTR_CTRL   (1 << 0)

Macro defines for UART Modem Control Register.

Source for modem output pin DTR

Definition at line 189 of file uart_11xx.h.

◆ UART_MCR_LOOPB_EN

#define UART_MCR_LOOPB_EN   (1 << 4)

Loop back mode select

Definition at line 191 of file uart_11xx.h.

◆ UART_MCR_RTS_CTRL

#define UART_MCR_RTS_CTRL   (1 << 1)

Source for modem output pin RTS

Definition at line 190 of file uart_11xx.h.

◆ UART_MSR_BITMASK

#define UART_MSR_BITMASK   (0xFF)

Modem status: MSR register bit-mask value

Definition at line 222 of file uart_11xx.h.

◆ UART_MSR_CTS

#define UART_MSR_CTS   (1 << 4)

Modem status: Clear To Send State

Definition at line 218 of file uart_11xx.h.

◆ UART_MSR_DCD

#define UART_MSR_DCD   (1 << 7)

Modem status: Data Carrier Detect State

Definition at line 221 of file uart_11xx.h.

◆ UART_MSR_DELTA_CTS

#define UART_MSR_DELTA_CTS   (1 << 0)

Macro defines for UART Modem Status Register.

Modem status: State change of input CTS

Definition at line 214 of file uart_11xx.h.

◆ UART_MSR_DELTA_DCD

#define UART_MSR_DELTA_DCD   (1 << 3)

Modem status: State change of input DCD

Definition at line 217 of file uart_11xx.h.

◆ UART_MSR_DELTA_DSR

#define UART_MSR_DELTA_DSR   (1 << 1)

Modem status: State change of input DSR

Definition at line 215 of file uart_11xx.h.

◆ UART_MSR_DSR

#define UART_MSR_DSR   (1 << 5)

Modem status: Data Set Ready State

Definition at line 219 of file uart_11xx.h.

◆ UART_MSR_LO2HI_RI

#define UART_MSR_LO2HI_RI   (1 << 2)

Modem status: Low to high transition of input RI

Definition at line 216 of file uart_11xx.h.

◆ UART_MSR_RI

#define UART_MSR_RI   (1 << 6)

Modem status: Ring Indicator State

Definition at line 220 of file uart_11xx.h.

◆ UART_RBR_MASKBIT

#define UART_RBR_MASKBIT   (0xFF)

Macro defines for UART Receive Buffer register.

UART Received Buffer mask bit (8 bits)

Definition at line 98 of file uart_11xx.h.

◆ UART_RS485CTRL_AADEN

#define UART_RS485CTRL_AADEN   (1 << 2)

Auto Address Detect (AAD) is enabled

Definition at line 239 of file uart_11xx.h.

◆ UART_RS485CTRL_BITMASK

#define UART_RS485CTRL_BITMASK   (0x3F)

RS485 control bit-mask value

Definition at line 246 of file uart_11xx.h.

◆ UART_RS485CTRL_DCTRL_EN

#define UART_RS485CTRL_DCTRL_EN   (1 << 4)

Enable Auto Direction Control

Definition at line 242 of file uart_11xx.h.

◆ UART_RS485CTRL_NMM_EN

#define UART_RS485CTRL_NMM_EN   (1 << 0)

Macro defines for UART RS485 Control register.

RS-485/EIA-485 Normal Multi-drop Mode (NMM) is disabled

Definition at line 237 of file uart_11xx.h.

◆ UART_RS485CTRL_OINV_1

#define UART_RS485CTRL_OINV_1   (1 << 5)

This bit reverses the polarity of the direction control signal on the RTS (or DTR) pin. The direction control pin will be driven to logic "1" when the transmitter has data to be sent

Definition at line 243 of file uart_11xx.h.

◆ UART_RS485CTRL_RX_DIS

#define UART_RS485CTRL_RX_DIS   (1 << 1)

The receiver is disabled

Definition at line 238 of file uart_11xx.h.

◆ UART_RS485CTRL_SEL_DTR

#define UART_RS485CTRL_SEL_DTR   (1 << 3)

If direction control is enabled (bit DCTRL = 1), pin DTR is used for direction control

Definition at line 240 of file uart_11xx.h.

◆ UART_SCICTRL_GUARDTIME

#define UART_SCICTRL_GUARDTIME (   n)    ((n & 0xFF) << 8)

Extra guard time

Definition at line 269 of file uart_11xx.h.

◆ UART_SCICTRL_NACKDIS

#define UART_SCICTRL_NACKDIS   (1 << 1)

NACK response is inhibited

Definition at line 266 of file uart_11xx.h.

◆ UART_SCICTRL_PROTSEL_T1

#define UART_SCICTRL_PROTSEL_T1   (1 << 2)

ISO7816-3 protocol T1 is selected

Definition at line 267 of file uart_11xx.h.

◆ UART_SCICTRL_SCIEN

#define UART_SCICTRL_SCIEN   (1 << 0)

Macro defines for UART Smart card interface Control Register - valid for 11xx, 18xx/43xx UART0/2/3 only.

enable asynchronous half-duplex smart card interface

Definition at line 265 of file uart_11xx.h.

◆ UART_SCICTRL_TXRETRY

#define UART_SCICTRL_TXRETRY (   n)    ((n & 0x07) << 5)

number of retransmission

Definition at line 268 of file uart_11xx.h.

◆ UART_SYNCCTRL_CCCLR

#define UART_SYNCCTRL_CCCLR   (1 << 6)

stop continuous clock

Definition at line 293 of file uart_11xx.h.

◆ UART_SYNCCTRL_CSCEN

#define UART_SYNCCTRL_CSCEN   (1 << 4)

Continuous running clock enable (master mode only)

Definition at line 291 of file uart_11xx.h.

◆ UART_SYNCCTRL_CSRC_MASTER

#define UART_SYNCCTRL_CSRC_MASTER   (1 << 1)

synchronous master mode

Definition at line 288 of file uart_11xx.h.

◆ UART_SYNCCTRL_FES

#define UART_SYNCCTRL_FES   (1 << 2)

sample on falling edge

Definition at line 289 of file uart_11xx.h.

◆ UART_SYNCCTRL_STARTSTOPDISABLE

#define UART_SYNCCTRL_STARTSTOPDISABLE   (1 << 5)

Do not send start/stop bit

Definition at line 292 of file uart_11xx.h.

◆ UART_SYNCCTRL_SYNC

#define UART_SYNCCTRL_SYNC   (1 << 0)

Macro defines for UART Synchronous Control Register - 11xx, 18xx/43xx UART0/2/3 only.

enable synchronous mode

Definition at line 287 of file uart_11xx.h.

◆ UART_SYNCCTRL_TSBYPASS

#define UART_SYNCCTRL_TSBYPASS   (1 << 3)

to be defined

Definition at line 290 of file uart_11xx.h.

◆ UART_TER1_TXEN

#define UART_TER1_TXEN   (1 << 7)

Macro defines for UART Tx Enable Register.

Transmit enable bit - valid for 11xx, 13xx, 17xx/40xx only

Definition at line 281 of file uart_11xx.h.

◆ UART_TER2_TXEN

#define UART_TER2_TXEN   (1 << 0)

Transmit enable bit - valid for 18xx/43xx only

Definition at line 282 of file uart_11xx.h.

◆ UART_TX_FIFO_SIZE

#define UART_TX_FIFO_SIZE   (16)

Definition at line 152 of file uart_11xx.h.

Function Documentation

◆ Chip_UART_ClearAutoBaudReg()

STATIC INLINE void Chip_UART_ClearAutoBaudReg ( LPC_USART_T pUART,
uint32_t  acr 
)

Clear autobaud register options.

Parameters
pUART: Pointer to selected UART peripheral
acr: Or'ed values to clear for ACR register
Returns
Nothing
Note
Use an Or'ed value of UART_ACR_* definitions with this call to clear specific options.

Definition at line 564 of file uart_11xx.h.

◆ Chip_UART_ClearModemControl()

STATIC INLINE void Chip_UART_ClearModemControl ( LPC_USART_T pUART,
uint32_t  mcr 
)

Clear modem control register/status.

Parameters
pUART: Pointer to selected UART peripheral
mcr: Modem control register flags to clear
Returns
Nothing
Note
Use an Or'ed value of UART_MCR_* definitions with this call to clear specific options.

Definition at line 493 of file uart_11xx.h.

◆ Chip_UART_ClearRS485Flags()

STATIC INLINE void Chip_UART_ClearRS485Flags ( LPC_USART_T pUART,
uint32_t  ctrl 
)

Clear RS485 control register options.

Parameters
pUART: Pointer to selected UART peripheral
ctrl: Or'ed values to clear for RS485 control register
Returns
Nothing
Note
Use an Or'ed value of UART_RS485CTRL_* definitions with this call to clear specific options.

Definition at line 590 of file uart_11xx.h.

◆ Chip_UART_ConfigData()

STATIC INLINE void Chip_UART_ConfigData ( LPC_USART_T pUART,
uint32_t  config 
)

Configure data width, parity and stop bits.

Parameters
pUART: Pointer to selected pUART peripheral
config: UART configuration, OR'ed values of UART_LCR_* defines
Returns
Nothing
Note
Select OR'ed config options for the UART from the UART_LCR_* definitions. For example, a configuration of 8 data bits, 1 stop bit, and even (enabled) parity would be (UART_LCR_WLEN8 | UART_LCR_SBS_1BIT | UART_LCR_PARITY_EN | UART_LCR_PARITY_EVEN)

Definition at line 419 of file uart_11xx.h.

◆ Chip_UART_DeInit()

void Chip_UART_DeInit ( LPC_USART_T pUART)

De-initializes the pUART peripheral.

Parameters
pUART: Pointer to selected pUART peripheral
Returns
Nothing

Definition at line 74 of file uart_11xx.c.

◆ Chip_UART_DisableDivisorAccess()

STATIC INLINE void Chip_UART_DisableDivisorAccess ( LPC_USART_T pUART)

Disable access to Divisor Latches.

Parameters
pUART: Pointer to selected UART peripheral
Returns
Nothing

Definition at line 439 of file uart_11xx.h.

◆ Chip_UART_EnableDivisorAccess()

STATIC INLINE void Chip_UART_EnableDivisorAccess ( LPC_USART_T pUART)

Enable access to Divisor Latches.

Parameters
pUART: Pointer to selected UART peripheral
Returns
Nothing

Definition at line 429 of file uart_11xx.h.

◆ Chip_UART_GetIntsEnabled()

STATIC INLINE uint32_t Chip_UART_GetIntsEnabled ( LPC_USART_T pUART)

Returns UART interrupts that are enabled.

Parameters
pUART: Pointer to selected UART peripheral
Returns
Returns the enabled UART interrupts
Note
Use an OR'ed value of UART_IER_* definitions with this function to determine which interrupts are enabled. You can check for multiple enabled bits if needed.

Definition at line 379 of file uart_11xx.h.

◆ Chip_UART_GetRS485Addr()

STATIC INLINE uint8_t Chip_UART_GetRS485Addr ( LPC_USART_T pUART)

Read RS485 address match value.

Parameters
pUART: Pointer to selected UART peripheral
Returns
Address match value for RS-485/EIA-485 mode

Definition at line 611 of file uart_11xx.h.

◆ Chip_UART_GetRS485Delay()

STATIC INLINE uint8_t Chip_UART_GetRS485Delay ( LPC_USART_T pUART)

Read RS485 direction control (RTS or DTR) delay value.

Parameters
pUART: Pointer to selected UART peripheral
Returns
direction control (RTS or DTR) delay value
Note
This delay time is in periods of the baud clock. Any delay time from 0 to 255 bit times may be programmed.

Definition at line 636 of file uart_11xx.h.

◆ Chip_UART_Init()

void Chip_UART_Init ( LPC_USART_T pUART)

Initializes the pUART peripheral.

Parameters
pUART: Pointer to selected pUART peripheral
Returns
Nothing

Definition at line 58 of file uart_11xx.c.

◆ Chip_UART_IntDisable()

STATIC INLINE void Chip_UART_IntDisable ( LPC_USART_T pUART,
uint32_t  intMask 
)

Disable UART interrupts.

Parameters
pUART: Pointer to selected UART peripheral
intMask: OR'ed Interrupts to disable in the Interrupt Enable Register (IER)
Returns
Nothing
Note
Use an OR'ed value of UART_IER_* definitions with this function to disable specific UART interrupts. The Divisor Latch Access Bit (DLAB) in LCR must be cleared in order to access the IER register. This function doesn't alter the DLAB state

Definition at line 366 of file uart_11xx.h.

◆ Chip_UART_IntEnable()

STATIC INLINE void Chip_UART_IntEnable ( LPC_USART_T pUART,
uint32_t  intMask 
)

Enable UART interrupts.

Parameters
pUART: Pointer to selected UART peripheral
intMask: OR'ed Interrupts to enable in the Interrupt Enable Register (IER)
Returns
Nothing
Note
Use an OR'ed value of UART_IER_* definitions with this function to enable specific UART interrupts. The Divisor Latch Access Bit (DLAB) in LCR must be cleared in order to access the IER register. This function doesn't alter the DLAB state

Definition at line 351 of file uart_11xx.h.

◆ Chip_UART_IRQRBHandler()

void Chip_UART_IRQRBHandler ( LPC_USART_T pUART,
RINGBUFF_T pRXRB,
RINGBUFF_T pTXRB 
)

UART receive/transmit interrupt handler for ring buffers.

Parameters
pUART: Pointer to selected UART peripheral
pRXRB: Pointer to transmit ring buffer
pTXRB: Pointer to receive ring buffer
Returns
Nothing
Note
This provides a basic implementation of the UART IRQ handler for support of a ring buffer implementation for transmit and receive.

Definition at line 220 of file uart_11xx.c.

◆ Chip_UART_Read()

int Chip_UART_Read ( LPC_USART_T pUART,
void *  data,
int  numBytes 
)

Read data through the UART peripheral (non-blocking)

Parameters
pUART: Pointer to selected UART peripheral
data: Pointer to bytes array to fill
numBytes: Size of the passed data array
Returns
The actual number of bytes read
Note
This function reads data from the receive FIFO until either all the data has been read or the passed buffer is completely full. This function will not block. This function ignores errors.

Definition at line 113 of file uart_11xx.c.

◆ Chip_UART_ReadBlocking()

int Chip_UART_ReadBlocking ( LPC_USART_T pUART,
void *  data,
int  numBytes 
)

Read data through the UART peripheral (blocking)

Parameters
pUART: Pointer to selected UART peripheral
data: Pointer to data array to fill
numBytes: Size of the passed data array
Returns
The size of the dat array
Note
This function reads data from the receive FIFO until the passed buffer is completely full. The function will block until full. This function ignores errors.

Definition at line 130 of file uart_11xx.c.

◆ Chip_UART_ReadByte()

STATIC INLINE uint8_t Chip_UART_ReadByte ( LPC_USART_T pUART)

Read a single byte data from the UART peripheral.

Parameters
pUART: Pointer to selected UART peripheral
Returns
A single byte of data read
Note
This function reads a byte from the UART receive FIFO or receive hold register regard regardless of UART state. The FIFO status should be read first prior to using this function

Definition at line 336 of file uart_11xx.h.

◆ Chip_UART_ReadIntIDReg()

STATIC INLINE uint32_t Chip_UART_ReadIntIDReg ( LPC_USART_T pUART)

Read the Interrupt Identification Register (IIR)

Parameters
pUART: Pointer to selected UART peripheral
Returns
Current pending interrupt status per the IIR register

Definition at line 389 of file uart_11xx.h.

◆ Chip_UART_ReadLineStatus()

STATIC INLINE uint32_t Chip_UART_ReadLineStatus ( LPC_USART_T pUART)

Return Line Status register/status (LSR)

Parameters
pUART: Pointer to selected UART peripheral
Returns
Line Status register (status)
Note
Mask bits of the returned status value with UART_LSR_* definitions for specific statuses.

Definition at line 505 of file uart_11xx.h.

◆ Chip_UART_ReadModemControl()

STATIC INLINE uint32_t Chip_UART_ReadModemControl ( LPC_USART_T pUART)

Return modem control register/status.

Parameters
pUART: Pointer to selected UART peripheral
Returns
Modem control register (status)
Note
Mask bits of the returned status value with UART_MCR_* definitions for specific statuses.

Definition at line 467 of file uart_11xx.h.

◆ Chip_UART_ReadModemStatus()

STATIC INLINE uint32_t Chip_UART_ReadModemStatus ( LPC_USART_T pUART)

Return Modem Status register/status (MSR)

Parameters
pUART: Pointer to selected UART peripheral
Returns
Modem Status register (status)
Note
Mask bits of the returned status value with UART_MSR_* definitions for specific statuses.

Definition at line 517 of file uart_11xx.h.

◆ Chip_UART_ReadRB()

int Chip_UART_ReadRB ( LPC_USART_T pUART,
RINGBUFF_T pRB,
void *  data,
int  bytes 
)

Copy data from a receive ring buffer.

Parameters
pUART: Pointer to selected UART peripheral
pRB: Pointer to ring buffer structure to use
data: Pointer to buffer to fill from ring buffer
bytes: Size of the passed buffer in bytes
Returns
The number of bytes placed into the ring buffer
Note
Will move the data from the RX ring buffer up to the the maximum passed buffer size. Returns 0 if there is no data in the ring buffer.

Definition at line 212 of file uart_11xx.c.

◆ Chip_UART_ReadScratch()

STATIC INLINE uint8_t Chip_UART_ReadScratch ( LPC_USART_T pUART)

Returns current byte value in the scratchpad register.

Parameters
pUART: Pointer to selected UART peripheral
Returns
Byte value read from scratchpad register

Definition at line 538 of file uart_11xx.h.

◆ Chip_UART_RXIntHandlerRB()

void Chip_UART_RXIntHandlerRB ( LPC_USART_T pUART,
RINGBUFF_T pRB 
)

UART receive-only interrupt handler for ring buffers.

Parameters
pUART: Pointer to selected UART peripheral
pRB: Pointer to ring buffer structure to use
Returns
Nothing
Note
If ring buffer support is desired for the receive side of data transfer, the UART interrupt should call this function for a receive based interrupt status.

Definition at line 168 of file uart_11xx.c.

◆ Chip_UART_Send()

int Chip_UART_Send ( LPC_USART_T pUART,
const void *  data,
int  numBytes 
)

Transmit a byte array through the UART peripheral (non-blocking)

Parameters
pUART: Pointer to selected UART peripheral
data: Pointer to bytes to transmit
numBytes: Number of bytes to transmit
Returns
The actual number of bytes placed into the FIFO
Note
This function places data into the transmit FIFO until either all the data is in the FIFO or the FIFO is full. This function will not block in the FIFO is full. The actual number of bytes placed into the FIFO is returned. This function ignores errors.

Definition at line 80 of file uart_11xx.c.

◆ Chip_UART_SendBlocking()

int Chip_UART_SendBlocking ( LPC_USART_T pUART,
const void *  data,
int  numBytes 
)

Transmit a byte array through the UART peripheral (blocking)

Parameters
pUART: Pointer to selected UART peripheral
data: Pointer to data to transmit
numBytes: Number of bytes to transmit
Returns
The number of bytes transmitted
Note
This function will send or place all bytes into the transmit FIFO. This function will block until the last bytes are in the FIFO.

Definition at line 97 of file uart_11xx.c.

◆ Chip_UART_SendByte()

STATIC INLINE void Chip_UART_SendByte ( LPC_USART_T pUART,
uint8_t  data 
)

Transmit a single data byte through the UART peripheral.

Parameters
pUART: Pointer to selected UART peripheral
data: Byte to transmit
Returns
Nothing
Note
This function attempts to place a byte into the UART transmit FIFO or transmit hold register regard regardless of UART state

Definition at line 323 of file uart_11xx.h.

◆ Chip_UART_SendRB()

uint32_t Chip_UART_SendRB ( LPC_USART_T pUART,
RINGBUFF_T pRB,
const void *  data,
int  bytes 
)

Populate a transmit ring buffer and start UART transmit.

Parameters
pUART: Pointer to selected UART peripheral
pRB: Pointer to ring buffer structure to use
data: Pointer to buffer to move to ring buffer
bytes: Number of bytes to move
Returns
The number of bytes placed into the ring buffer
Note
Will move the data into the TX ring buffer and start the transfer. If the number of bytes returned is less than the number of bytes to send, the ring buffer is considered full.

Definition at line 190 of file uart_11xx.c.

◆ Chip_UART_SetAutoBaudReg()

STATIC INLINE void Chip_UART_SetAutoBaudReg ( LPC_USART_T pUART,
uint32_t  acr 
)

Set autobaud register options.

Parameters
pUART: Pointer to selected UART peripheral
acr: Or'ed values to set for ACR register
Returns
Nothing
Note
Use an Or'ed value of UART_ACR_* definitions with this call to set specific options.

Definition at line 551 of file uart_11xx.h.

◆ Chip_UART_SetBaud()

uint32_t Chip_UART_SetBaud ( LPC_USART_T pUART,
uint32_t  baudrate 
)

Sets best dividers to get a target bit rate (without fractional divider)

Parameters
pUART: Pointer to selected UART peripheral
baudrate: Target baud rate (baud rate = bit rate)
Returns
The actual baud rate, or 0 if no rate can be found

Definition at line 146 of file uart_11xx.c.

◆ Chip_UART_SetBaudFDR()

uint32_t Chip_UART_SetBaudFDR ( LPC_USART_T pUART,
uint32_t  baudrate 
)

Sets best dividers to get a target bit rate (with fractional divider)

Parameters
pUART: Pointer to selected UART peripheral
baudrate: Target baud rate (baud rate = bit rate)
Returns
The actual baud rate, or 0 if no rate can be found

Definition at line 237 of file uart_11xx.c.

◆ Chip_UART_SetDivisorLatches()

STATIC INLINE void Chip_UART_SetDivisorLatches ( LPC_USART_T pUART,
uint8_t  dll,
uint8_t  dlm 
)

Set LSB and MSB divisor latch registers.

Parameters
pUART: Pointer to selected UART peripheral
dll: Divisor Latch LSB value
dlm: Divisor Latch MSB value
Returns
Nothing
Note
The Divisor Latch Access Bit (DLAB) in LCR must be set in order to access the USART Divisor Latches. This function doesn't alter the DLAB state.

Definition at line 454 of file uart_11xx.h.

◆ Chip_UART_SetModemControl()

STATIC INLINE void Chip_UART_SetModemControl ( LPC_USART_T pUART,
uint32_t  mcr 
)

Set modem control register/status.

Parameters
pUART: Pointer to selected UART peripheral
mcr: Modem control register flags to set
Returns
Nothing
Note
Use an Or'ed value of UART_MCR_* definitions with this call to set specific options.

Definition at line 480 of file uart_11xx.h.

◆ Chip_UART_SetRS485Addr()

STATIC INLINE void Chip_UART_SetRS485Addr ( LPC_USART_T pUART,
uint8_t  addr 
)

Set RS485 address match value.

Parameters
pUART: Pointer to selected UART peripheral
addr: Address match value for RS-485/EIA-485 mode
Returns
Nothing

Definition at line 601 of file uart_11xx.h.

◆ Chip_UART_SetRS485Delay()

STATIC INLINE void Chip_UART_SetRS485Delay ( LPC_USART_T pUART,
uint8_t  dly 
)

Set RS485 direction control (RTS or DTR) delay value.

Parameters
pUART: Pointer to selected UART peripheral
dly: direction control (RTS or DTR) delay value
Returns
Nothing
Note
This delay time is in periods of the baud clock. Any delay time from 0 to 255 bit times may be programmed.

Definition at line 624 of file uart_11xx.h.

◆ Chip_UART_SetRS485Flags()

STATIC INLINE void Chip_UART_SetRS485Flags ( LPC_USART_T pUART,
uint32_t  ctrl 
)

Set RS485 control register options.

Parameters
pUART: Pointer to selected UART peripheral
ctrl: Or'ed values to set for RS485 control register
Returns
Nothing
Note
Use an Or'ed value of UART_RS485CTRL_* definitions with this call to set specific options.

Definition at line 577 of file uart_11xx.h.

◆ Chip_UART_SetScratch()

STATIC INLINE void Chip_UART_SetScratch ( LPC_USART_T pUART,
uint8_t  data 
)

Write a byte to the scratchpad register.

Parameters
pUART: Pointer to selected UART peripheral
data: Byte value to write
Returns
Nothing

Definition at line 528 of file uart_11xx.h.

◆ Chip_UART_SetupFIFOS()

STATIC INLINE void Chip_UART_SetupFIFOS ( LPC_USART_T pUART,
uint32_t  fcr 
)

Setup the UART FIFOs.

Parameters
pUART: Pointer to selected UART peripheral
fcr: FIFO control register setup OR'ed flags
Returns
Nothing
Note
Use OR'ed value of UART_FCR_* definitions with this function to select specific options. For example, to enable the FIFOs with a RX trip level of 8 characters, use something like (UART_FCR_FIFO_EN | UART_FCR_TRG_LEV2)

Definition at line 404 of file uart_11xx.h.

◆ Chip_UART_TXDisable()

STATIC INLINE void Chip_UART_TXDisable ( LPC_USART_T pUART)

Disable transmission on UART TxD pin.

Parameters
pUART: Pointer to selected pUART peripheral
Returns
Nothing

Definition at line 310 of file uart_11xx.h.

◆ Chip_UART_TXEnable()

STATIC INLINE void Chip_UART_TXEnable ( LPC_USART_T pUART)

Enable transmission on UART TxD pin.

Parameters
pUART: Pointer to selected pUART peripheral
Returns
Nothing

Definition at line 300 of file uart_11xx.h.

◆ Chip_UART_TXIntHandlerRB()

void Chip_UART_TXIntHandlerRB ( LPC_USART_T pUART,
RINGBUFF_T pRB 
)

UART transmit-only interrupt handler for ring buffers.

Parameters
pUART: Pointer to selected UART peripheral
pRB: Pointer to ring buffer structure to use
Returns
Nothing
Note
If ring buffer support is desired for the transmit side of data transfer, the UART interrupt should call this function for a transmit based interrupt status.

Definition at line 178 of file uart_11xx.c.



uavcan_communicator
Author(s):
autogenerated on Fri Dec 13 2024 03:10:04