32 #ifndef __UART_11XX_H_ 33 #define __UART_11XX_H_ 98 #define UART_RBR_MASKBIT (0xFF) 103 #define UART_LOAD_DLL(div) ((div) & 0xFF) 104 #define UART_DLL_MASKBIT (0xFF) 109 #define UART_LOAD_DLM(div) (((div) >> 8) & 0xFF) 110 #define UART_DLM_MASKBIT (0xFF) 115 #define UART_IER_RBRINT (1 << 0) 116 #define UART_IER_THREINT (1 << 1) 117 #define UART_IER_RLSINT (1 << 2) 118 #define UART_IER_MSINT (1 << 3) 119 #define UART_IER_CTSINT (1 << 7) 120 #define UART_IER_ABEOINT (1 << 8) 121 #define UART_IER_ABTOINT (1 << 9) 122 #define UART_IER_BITMASK (0x307) 123 #define UART1_IER_BITMASK (0x30F) 124 #define UART2_IER_BITMASK (0x38F) 129 #define UART_IIR_INTSTAT_PEND (1 << 0) 130 #define UART_IIR_FIFO_EN (3 << 6) 131 #define UART_IIR_ABEO_INT (1 << 8) 132 #define UART_IIR_ABTO_INT (1 << 9) 133 #define UART_IIR_BITMASK (0x3CF) 136 #define UART_IIR_INTID_MASK (7 << 1) 137 #define UART_IIR_INTID_RLS (3 << 1) 138 #define UART_IIR_INTID_RDA (2 << 1) 139 #define UART_IIR_INTID_CTI (6 << 1) 140 #define UART_IIR_INTID_THRE (1 << 1) 141 #define UART_IIR_INTID_MODEM (0 << 1) 146 #define UART_FCR_FIFO_EN (1 << 0) 147 #define UART_FCR_RX_RS (1 << 1) 148 #define UART_FCR_TX_RS (1 << 2) 149 #define UART_FCR_DMAMODE_SEL (1 << 3) 150 #define UART_FCR_BITMASK (0xCF) 152 #define UART_TX_FIFO_SIZE (16) 155 #define UART_FCR_TRG_LEV0 (0) 156 #define UART_FCR_TRG_LEV1 (1 << 6) 157 #define UART_FCR_TRG_LEV2 (2 << 6) 158 #define UART_FCR_TRG_LEV3 (3 << 6) 164 #define UART_LCR_WLEN_MASK (3 << 0) 165 #define UART_LCR_WLEN5 (0 << 0) 166 #define UART_LCR_WLEN6 (1 << 0) 167 #define UART_LCR_WLEN7 (2 << 0) 168 #define UART_LCR_WLEN8 (3 << 0) 171 #define UART_LCR_SBS_MASK (1 << 2) 172 #define UART_LCR_SBS_1BIT (0 << 2) 173 #define UART_LCR_SBS_2BIT (1 << 2) 176 #define UART_LCR_PARITY_EN (1 << 3) 177 #define UART_LCR_PARITY_DIS (0 << 3) 178 #define UART_LCR_PARITY_ODD (0 << 4) 179 #define UART_LCR_PARITY_EVEN (1 << 4) 180 #define UART_LCR_PARITY_F_1 (2 << 4) 181 #define UART_LCR_PARITY_F_0 (3 << 4) 182 #define UART_LCR_BREAK_EN (1 << 6) 183 #define UART_LCR_DLAB_EN (1 << 7) 184 #define UART_LCR_BITMASK (0xFF) 189 #define UART_MCR_DTR_CTRL (1 << 0) 190 #define UART_MCR_RTS_CTRL (1 << 1) 191 #define UART_MCR_LOOPB_EN (1 << 4) 192 #define UART_MCR_AUTO_RTS_EN (1 << 6) 193 #define UART_MCR_AUTO_CTS_EN (1 << 7) 194 #define UART_MCR_BITMASK (0xD3) 199 #define UART_LSR_RDR (1 << 0) 200 #define UART_LSR_OE (1 << 1) 201 #define UART_LSR_PE (1 << 2) 202 #define UART_LSR_FE (1 << 3) 203 #define UART_LSR_BI (1 << 4) 204 #define UART_LSR_THRE (1 << 5) 205 #define UART_LSR_TEMT (1 << 6) 206 #define UART_LSR_RXFE (1 << 7) 207 #define UART_LSR_TXFE (1 << 8) 208 #define UART_LSR_BITMASK (0xFF) 209 #define UART1_LSR_BITMASK (0x1FF) 214 #define UART_MSR_DELTA_CTS (1 << 0) 215 #define UART_MSR_DELTA_DSR (1 << 1) 216 #define UART_MSR_LO2HI_RI (1 << 2) 217 #define UART_MSR_DELTA_DCD (1 << 3) 218 #define UART_MSR_CTS (1 << 4) 219 #define UART_MSR_DSR (1 << 5) 220 #define UART_MSR_RI (1 << 6) 221 #define UART_MSR_DCD (1 << 7) 222 #define UART_MSR_BITMASK (0xFF) 227 #define UART_ACR_START (1 << 0) 228 #define UART_ACR_MODE (1 << 1) 229 #define UART_ACR_AUTO_RESTART (1 << 2) 230 #define UART_ACR_ABEOINT_CLR (1 << 8) 231 #define UART_ACR_ABTOINT_CLR (1 << 9) 232 #define UART_ACR_BITMASK (0x307) 237 #define UART_RS485CTRL_NMM_EN (1 << 0) 238 #define UART_RS485CTRL_RX_DIS (1 << 1) 239 #define UART_RS485CTRL_AADEN (1 << 2) 240 #define UART_RS485CTRL_SEL_DTR (1 << 3) 242 #define UART_RS485CTRL_DCTRL_EN (1 << 4) 243 #define UART_RS485CTRL_OINV_1 (1 << 5) 246 #define UART_RS485CTRL_BITMASK (0x3F) 251 #define UART_ICR_IRDAEN (1 << 0) 252 #define UART_ICR_IRDAINV (1 << 1) 253 #define UART_ICR_FIXPULSE_EN (1 << 2) 254 #define UART_ICR_PULSEDIV(n) ((n & 0x07) << 3) 255 #define UART_ICR_BITMASK (0x3F) 260 #define UART_HDEN_HDEN ((1 << 0)) 265 #define UART_SCICTRL_SCIEN (1 << 0) 266 #define UART_SCICTRL_NACKDIS (1 << 1) 267 #define UART_SCICTRL_PROTSEL_T1 (1 << 2) 268 #define UART_SCICTRL_TXRETRY(n) ((n & 0x07) << 5) 269 #define UART_SCICTRL_GUARDTIME(n) ((n & 0xFF) << 8) 274 #define UART_FDR_DIVADDVAL(n) (n & 0x0F) 275 #define UART_FDR_MULVAL(n) ((n << 4) & 0xF0) 276 #define UART_FDR_BITMASK (0xFF) 281 #define UART_TER1_TXEN (1 << 7) 282 #define UART_TER2_TXEN (1 << 0) 287 #define UART_SYNCCTRL_SYNC (1 << 0) 288 #define UART_SYNCCTRL_CSRC_MASTER (1 << 1) 289 #define UART_SYNCCTRL_FES (1 << 2) 290 #define UART_SYNCCTRL_TSBYPASS (1 << 3) 291 #define UART_SYNCCTRL_CSCEN (1 << 4) 292 #define UART_SYNCCTRL_STARTSTOPDISABLE (1 << 5) 293 #define UART_SYNCCTRL_CCCLR (1 << 6) 300 STATIC INLINE void Chip_UART_TXEnable(LPC_USART_T *pUART) 353 pUART->
IER |= intMask;
368 pUART->
IER &= ~intMask;
STATIC INLINE void Chip_UART_SetScratch(LPC_USART_T *pUART, uint8_t data)
Write a byte to the scratchpad register.
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.
STATIC INLINE void Chip_UART_SetupFIFOS(LPC_USART_T *pUART, uint32_t fcr)
Setup the UART FIFOs.
STATIC INLINE uint8_t Chip_UART_ReadByte(LPC_USART_T *pUART)
Read a single byte data from the UART peripheral.
void Chip_UART_Init(LPC_USART_T *pUART)
Initializes the pUART peripheral.
STATIC INLINE uint32_t Chip_UART_ReadLineStatus(LPC_USART_T *pUART)
Return Line Status register/status (LSR)
int Chip_UART_Send(LPC_USART_T *pUART, const void *data, int numBytes)
Transmit a byte array through the UART peripheral (non-blocking)
STATIC INLINE void Chip_UART_SetRS485Delay(LPC_USART_T *pUART, uint8_t dly)
Set RS485 direction control (RTS or DTR) delay value.
STATIC INLINE void Chip_UART_ClearAutoBaudReg(LPC_USART_T *pUART, uint32_t acr)
Clear autobaud register options.
STATIC INLINE void Chip_UART_SetDivisorLatches(LPC_USART_T *pUART, uint8_t dll, uint8_t dlm)
Set LSB and MSB divisor latch registers.
void Chip_UART_TXIntHandlerRB(LPC_USART_T *pUART, RINGBUFF_T *pRB)
UART transmit-only interrupt handler for ring buffers.
STATIC INLINE uint8_t Chip_UART_GetRS485Addr(LPC_USART_T *pUART)
Read RS485 address match value.
STATIC INLINE void Chip_UART_SendByte(LPC_USART_T *pUART, uint8_t data)
Transmit a single data byte through the UART peripheral.
uint32_t Chip_UART_SetBaudFDR(LPC_USART_T *pUART, uint32_t baudrate)
Sets best dividers to get a target bit rate (with fractional divider)
STATIC INLINE void Chip_UART_ClearRS485Flags(LPC_USART_T *pUART, uint32_t ctrl)
Clear RS485 control register options.
STATIC INLINE void Chip_UART_ClearModemControl(LPC_USART_T *pUART, uint32_t mcr)
Clear modem control register/status.
int Chip_UART_SendBlocking(LPC_USART_T *pUART, const void *data, int numBytes)
Transmit a byte array through the UART peripheral (blocking)
STATIC INLINE uint32_t Chip_UART_GetIntsEnabled(LPC_USART_T *pUART)
Returns UART interrupts that are enabled.
STATIC INLINE void Chip_UART_DisableDivisorAccess(LPC_USART_T *pUART)
Disable access to Divisor Latches.
#define UART_TER1_TXEN
Macro defines for UART Tx Enable Register.
uint32_t Chip_UART_SetBaud(LPC_USART_T *pUART, uint32_t baudrate)
Sets best dividers to get a target bit rate (without fractional divider)
STATIC INLINE void Chip_UART_EnableDivisorAccess(LPC_USART_T *pUART)
Enable access to Divisor Latches.
STATIC INLINE void Chip_UART_SetRS485Addr(LPC_USART_T *pUART, uint8_t addr)
Set RS485 address match value.
USART register block structure.
void Chip_UART_RXIntHandlerRB(LPC_USART_T *pUART, RINGBUFF_T *pRB)
UART receive-only interrupt handler for ring buffers.
STATIC INLINE void Chip_UART_SetModemControl(LPC_USART_T *pUART, uint32_t mcr)
Set modem control register/status.
STATIC INLINE void Chip_UART_SetAutoBaudReg(LPC_USART_T *pUART, uint32_t acr)
Set autobaud register options.
STATIC INLINE void Chip_UART_IntDisable(LPC_USART_T *pUART, uint32_t intMask)
Disable UART interrupts.
STATIC INLINE void Chip_UART_SetRS485Flags(LPC_USART_T *pUART, uint32_t ctrl)
Set RS485 control register options.
void Chip_UART_DeInit(LPC_USART_T *pUART)
De-initializes the pUART peripheral.
STATIC INLINE void Chip_UART_ConfigData(LPC_USART_T *pUART, uint32_t config)
Configure data width, parity and stop bits.
int Chip_UART_ReadRB(LPC_USART_T *pUART, RINGBUFF_T *pRB, void *data, int bytes)
Copy data from a receive ring buffer.
void Chip_UART_IRQRBHandler(LPC_USART_T *pUART, RINGBUFF_T *pRXRB, RINGBUFF_T *pTXRB)
UART receive/transmit interrupt handler for ring buffers.
STATIC INLINE uint32_t Chip_UART_ReadModemControl(LPC_USART_T *pUART)
Return modem control register/status.
STATIC INLINE void Chip_UART_TXDisable(LPC_USART_T *pUART)
Disable transmission on UART TxD pin.
STATIC INLINE void Chip_UART_IntEnable(LPC_USART_T *pUART, uint32_t intMask)
Enable UART interrupts.
int Chip_UART_Read(LPC_USART_T *pUART, void *data, int numBytes)
Read data through the UART peripheral (non-blocking)
STATIC INLINE uint32_t Chip_UART_ReadIntIDReg(LPC_USART_T *pUART)
Read the Interrupt Identification Register (IIR)
int Chip_UART_ReadBlocking(LPC_USART_T *pUART, void *data, int numBytes)
Read data through the UART peripheral (blocking)
__IO uint32_t RS485ADRMATCH
STATIC INLINE uint32_t Chip_UART_ReadModemStatus(LPC_USART_T *pUART)
Return Modem Status register/status (MSR)
STATIC INLINE uint8_t Chip_UART_ReadScratch(LPC_USART_T *pUART)
Returns current byte value in the scratchpad register.
STATIC INLINE uint8_t Chip_UART_GetRS485Delay(LPC_USART_T *pUART)
Read RS485 direction control (RTS or DTR) delay value.
#define UART_RBR_MASKBIT
Macro defines for UART Receive Buffer register.