uart_11xx.h
Go to the documentation of this file.
1 /*
2  * @brief LPC11xx UART chip driver
3  *
4  * @note
5  * Copyright(C) NXP Semiconductors, 2012
6  * All rights reserved.
7  *
8  * @par
9  * Software that is described herein is for illustrative purposes only
10  * which provides customers with programming information regarding the
11  * LPC products. This software is supplied "AS IS" without any warranties of
12  * any kind, and NXP Semiconductors and its licensor disclaim any and
13  * all warranties, express or implied, including all implied warranties of
14  * merchantability, fitness for a particular purpose and non-infringement of
15  * intellectual property rights. NXP Semiconductors assumes no responsibility
16  * or liability for the use of the software, conveys no license or rights under any
17  * patent, copyright, mask work right, or any other intellectual property rights in
18  * or to any products. NXP Semiconductors reserves the right to make changes
19  * in the software without notification. NXP Semiconductors also makes no
20  * representation or warranty that such application will be suitable for the
21  * specified use without further testing or modification.
22  *
23  * @par
24  * Permission to use, copy, modify, and distribute this software and its
25  * documentation is hereby granted, under NXP Semiconductors' and its
26  * licensor's relevant copyrights in the software, without fee, provided that it
27  * is used in conjunction with NXP Semiconductors microcontrollers. This
28  * copyright, permission, and disclaimer notice must appear in all copies of
29  * this code.
30  */
31 
32 #ifndef __UART_11XX_H_
33 #define __UART_11XX_H_
34 
35 #include "ring_buffer.h"
36 
37 #ifdef __cplusplus
38 extern "C" {
39 #endif
40 
49 typedef struct {
51  union {
55  };
56 
57  union {
60  };
61 
62  union {
65  };
66 
77  uint32_t RESERVED0[3];
79  __I uint32_t RESERVED1[1];
86  union {
89  };
90 
92 } LPC_USART_T;
93 
94 
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)
135 /* Interrupt ID bit definitions */
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)
153 
154 /* FIFO trigger level bit definitions */
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)
163 /* UART word length select bit definitions */
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)
170 /* UART Stop bit select bit definitions */
171 #define UART_LCR_SBS_MASK (1 << 2)
172 #define UART_LCR_SBS_1BIT (0 << 2)
173 #define UART_LCR_SBS_2BIT (1 << 2)
175 /* UART Parity enable bit definitions */
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)
301 {
302  pUART->TER1 = UART_TER1_TXEN;
303 }
304 
311 {
312  pUART->TER1 = 0;
313 }
314 
324 {
325  pUART->THR = (uint32_t) data;
326 }
327 
337 {
338  return (uint8_t) (pUART->RBR & UART_RBR_MASKBIT);
339 }
340 
352 {
353  pUART->IER |= intMask;
354 }
355 
367 {
368  pUART->IER &= ~intMask;
369 }
370 
380 {
381  return pUART->IER;
382 }
383 
390 {
391  return pUART->IIR;
392 }
393 
405 {
406  pUART->FCR = fcr;
407 }
408 
420 {
421  pUART->LCR = config;
422 }
423 
430 {
431  pUART->LCR |= UART_LCR_DLAB_EN;
432 }
433 
440 {
441  pUART->LCR &= ~UART_LCR_DLAB_EN;
442 }
443 
455 {
456  pUART->DLL = (uint32_t) dll;
457  pUART->DLM = (uint32_t) dlm;
458 }
459 
468 {
469  return pUART->MCR;
470 }
471 
481 {
482  pUART->MCR |= mcr;
483 }
484 
494 {
495  pUART->MCR &= ~mcr;
496 }
497 
506 {
507  return pUART->LSR;
508 }
509 
518 {
519  return pUART->MSR;
520 }
521 
529 {
530  pUART->SCR = (uint32_t) data;
531 }
532 
539 {
540  return (uint8_t) (pUART->SCR & 0xFF);
541 }
542 
552 {
553  pUART->ACR |= acr;
554 }
555 
565 {
566  pUART->ACR &= ~acr;
567 }
568 
578 {
579  pUART->RS485CTRL |= ctrl;
580 }
581 
591 {
592  pUART->RS485CTRL &= ~ctrl;
593 }
594 
602 {
603  pUART->RS485ADRMATCH = (uint32_t) addr;
604 }
605 
612 {
613  return (uint8_t) (pUART->RS485ADRMATCH & 0xFF);
614 }
615 
625 {
626  pUART->RS485DLY = (uint32_t) dly;
627 }
628 
637 {
638  return (uint8_t) (pUART->RS485DLY & 0xFF);
639 }
640 
646 void Chip_UART_Init(LPC_USART_T *pUART);
647 
653 void Chip_UART_DeInit(LPC_USART_T *pUART);
654 
666 int Chip_UART_Send(LPC_USART_T *pUART, const void *data, int numBytes);
667 
678 int Chip_UART_Read(LPC_USART_T *pUART, void *data, int numBytes);
679 
687 
695 
705 int Chip_UART_SendBlocking(LPC_USART_T *pUART, const void *data, int numBytes);
706 
717 int Chip_UART_ReadBlocking(LPC_USART_T *pUART, void *data, int numBytes);
718 
729 
740 
752 uint32_t Chip_UART_SendRB(LPC_USART_T *pUART, RINGBUFF_T *pRB, const void *data, int bytes);
753 
765 int Chip_UART_ReadRB(LPC_USART_T *pUART, RINGBUFF_T *pRB, void *data, int bytes);
766 
777 void Chip_UART_IRQRBHandler(LPC_USART_T *pUART, RINGBUFF_T *pRXRB, RINGBUFF_T *pTXRB);
778 
783 #ifdef __cplusplus
784 }
785 #endif
786 
787 #endif /* __UART_11XX_H_ */
Chip_UART_DeInit
void Chip_UART_DeInit(LPC_USART_T *pUART)
De-initializes the pUART peripheral.
Definition: uart_11xx.c:74
Chip_UART_ReadScratch
STATIC INLINE uint8_t Chip_UART_ReadScratch(LPC_USART_T *pUART)
Returns current byte value in the scratchpad register.
Definition: uart_11xx.h:538
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.
Definition: uart_11xx.h:624
Chip_UART_DisableDivisorAccess
STATIC INLINE void Chip_UART_DisableDivisorAccess(LPC_USART_T *pUART)
Disable access to Divisor Latches.
Definition: uart_11xx.h:439
LPC_USART_T
USART register block structure.
Definition: uart_11xx.h:49
LPC_USART_T::DLM
__IO uint32_t DLM
Definition: uart_11xx.h:59
uavcan::uint32_t
std::uint32_t uint32_t
Definition: std.hpp:26
Chip_UART_ReadByte
STATIC INLINE uint8_t Chip_UART_ReadByte(LPC_USART_T *pUART)
Read a single byte data from the UART peripheral.
Definition: uart_11xx.h:336
LPC_USART_T::SCICTRL
__IO uint32_t SCICTRL
Definition: uart_11xx.h:80
LPC_USART_T::OSR
__IO uint32_t OSR
Definition: uart_11xx.h:75
Chip_UART_TXDisable
STATIC INLINE void Chip_UART_TXDisable(LPC_USART_T *pUART)
Disable transmission on UART TxD pin.
Definition: uart_11xx.h:310
__IO
#define __IO
Definition: core_cm0.h:154
LPC_USART_T::RS485DLY
__IO uint32_t RS485DLY
Definition: uart_11xx.h:84
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.
Definition: uart_11xx.c:220
Chip_UART_GetRS485Addr
STATIC INLINE uint8_t Chip_UART_GetRS485Addr(LPC_USART_T *pUART)
Read RS485 address match value.
Definition: uart_11xx.h:611
LPC_USART_T::MCR
__IO uint32_t MCR
Definition: uart_11xx.h:68
Chip_UART_SetModemControl
STATIC INLINE void Chip_UART_SetModemControl(LPC_USART_T *pUART, uint32_t mcr)
Set modem control register/status.
Definition: uart_11xx.h:480
__I
#define __I
Definition: core_cm0.h:151
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.
Definition: uart_11xx.h:323
Chip_UART_GetIntsEnabled
STATIC INLINE uint32_t Chip_UART_GetIntsEnabled(LPC_USART_T *pUART)
Returns UART interrupts that are enabled.
Definition: uart_11xx.h:379
Chip_UART_IntDisable
STATIC INLINE void Chip_UART_IntDisable(LPC_USART_T *pUART, uint32_t intMask)
Disable UART interrupts.
Definition: uart_11xx.h:366
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.
Definition: uart_11xx.c:212
Chip_UART_EnableDivisorAccess
STATIC INLINE void Chip_UART_EnableDivisorAccess(LPC_USART_T *pUART)
Enable access to Divisor Latches.
Definition: uart_11xx.h:429
LPC_USART_T::FDR
__IO uint32_t FDR
Definition: uart_11xx.h:74
Chip_UART_IntEnable
STATIC INLINE void Chip_UART_IntEnable(LPC_USART_T *pUART, uint32_t intMask)
Enable UART interrupts.
Definition: uart_11xx.h:351
Chip_UART_ClearModemControl
STATIC INLINE void Chip_UART_ClearModemControl(LPC_USART_T *pUART, uint32_t mcr)
Clear modem control register/status.
Definition: uart_11xx.h:493
INLINE
#define INLINE
Definition: lpc_types.h:205
Chip_UART_TXIntHandlerRB
void Chip_UART_TXIntHandlerRB(LPC_USART_T *pUART, RINGBUFF_T *pRB)
UART transmit-only interrupt handler for ring buffers.
Definition: uart_11xx.c:178
UART_RBR_MASKBIT
#define UART_RBR_MASKBIT
Macro defines for UART Receive Buffer register.
Definition: uart_11xx.h:98
uavcan::uint8_t
std::uint8_t uint8_t
Definition: std.hpp:24
UART_TER1_TXEN
#define UART_TER1_TXEN
Macro defines for UART Tx Enable Register.
Definition: uart_11xx.h:281
Chip_UART_RXIntHandlerRB
void Chip_UART_RXIntHandlerRB(LPC_USART_T *pUART, RINGBUFF_T *pRB)
UART receive-only interrupt handler for ring buffers.
Definition: uart_11xx.c:168
Chip_UART_GetRS485Delay
STATIC INLINE uint8_t Chip_UART_GetRS485Delay(LPC_USART_T *pUART)
Read RS485 direction control (RTS or DTR) delay value.
Definition: uart_11xx.h:636
LPC_USART_T::RS485CTRL
__IO uint32_t RS485CTRL
Definition: uart_11xx.h:82
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.
Definition: uart_11xx.h:454
RINGBUFF_T
Ring buffer structure.
Definition: ring_buffer.h:45
LPC_USART_T::LCR
__IO uint32_t LCR
Definition: uart_11xx.h:67
LPC_USART_T::SYNCCTRL
__IO uint32_t SYNCCTRL
Definition: uart_11xx.h:87
Chip_UART_SetAutoBaudReg
STATIC INLINE void Chip_UART_SetAutoBaudReg(LPC_USART_T *pUART, uint32_t acr)
Set autobaud register options.
Definition: uart_11xx.h:551
Chip_UART_ReadLineStatus
STATIC INLINE uint32_t Chip_UART_ReadLineStatus(LPC_USART_T *pUART)
Return Line Status register/status (LSR)
Definition: uart_11xx.h:505
LPC_USART_T::THR
__O uint32_t THR
Definition: uart_11xx.h:53
LPC_USART_T::LSR
__I uint32_t LSR
Definition: uart_11xx.h:69
Chip_UART_SetRS485Flags
STATIC INLINE void Chip_UART_SetRS485Flags(LPC_USART_T *pUART, uint32_t ctrl)
Set RS485 control register options.
Definition: uart_11xx.h:577
LPC_USART_T::HDEN
__IO uint32_t HDEN
Definition: uart_11xx.h:78
Chip_UART_ReadIntIDReg
STATIC INLINE uint32_t Chip_UART_ReadIntIDReg(LPC_USART_T *pUART)
Read the Interrupt Identification Register (IIR)
Definition: uart_11xx.h:389
Chip_UART_ConfigData
STATIC INLINE void Chip_UART_ConfigData(LPC_USART_T *pUART, uint32_t config)
Configure data width, parity and stop bits.
Definition: uart_11xx.h:419
LPC_USART_T::TER2
__IO uint32_t TER2
Definition: uart_11xx.h:91
Chip_UART_ReadModemStatus
STATIC INLINE uint32_t Chip_UART_ReadModemStatus(LPC_USART_T *pUART)
Return Modem Status register/status (MSR)
Definition: uart_11xx.h:517
LPC_USART_T::IER
__IO uint32_t IER
Definition: uart_11xx.h:58
__O
#define __O
Definition: core_cm0.h:153
LPC_USART_T::FIFOLVL
__I uint32_t FIFOLVL
Definition: uart_11xx.h:88
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)
Definition: uart_11xx.c:146
LPC_USART_T::RS485ADRMATCH
__IO uint32_t RS485ADRMATCH
Definition: uart_11xx.h:83
Chip_UART_SetScratch
STATIC INLINE void Chip_UART_SetScratch(LPC_USART_T *pUART, uint8_t data)
Write a byte to the scratchpad register.
Definition: uart_11xx.h:528
ring_buffer.h
Chip_UART_Init
void Chip_UART_Init(LPC_USART_T *pUART)
Initializes the pUART peripheral.
Definition: uart_11xx.c:58
Chip_UART_ClearRS485Flags
STATIC INLINE void Chip_UART_ClearRS485Flags(LPC_USART_T *pUART, uint32_t ctrl)
Clear RS485 control register options.
Definition: uart_11xx.h:590
Chip_UART_Read
int Chip_UART_Read(LPC_USART_T *pUART, void *data, int numBytes)
Read data through the UART peripheral (non-blocking)
Definition: uart_11xx.c:113
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)
Definition: uart_11xx.c:80
LPC_USART_T::FCR
__O uint32_t FCR
Definition: uart_11xx.h:63
UART_LCR_DLAB_EN
#define UART_LCR_DLAB_EN
Definition: uart_11xx.h:183
Chip_UART_ReadBlocking
int Chip_UART_ReadBlocking(LPC_USART_T *pUART, void *data, int numBytes)
Read data through the UART peripheral (blocking)
Definition: uart_11xx.c:130
LPC_USART_T::SCR
__IO uint32_t SCR
Definition: uart_11xx.h:71
LPC_USART_T::ACR
__IO uint32_t ACR
Definition: uart_11xx.h:72
Chip_UART_SetRS485Addr
STATIC INLINE void Chip_UART_SetRS485Addr(LPC_USART_T *pUART, uint8_t addr)
Set RS485 address match value.
Definition: uart_11xx.h:601
Chip_UART_ClearAutoBaudReg
STATIC INLINE void Chip_UART_ClearAutoBaudReg(LPC_USART_T *pUART, uint32_t acr)
Clear autobaud register options.
Definition: uart_11xx.h:564
LPC_USART_T::MSR
__I uint32_t MSR
Definition: uart_11xx.h:70
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)
Definition: uart_11xx.c:237
LPC_USART_T::RBR
__I uint32_t RBR
Definition: uart_11xx.h:54
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.
Definition: uart_11xx.c:190
Chip_UART_ReadModemControl
STATIC INLINE uint32_t Chip_UART_ReadModemControl(LPC_USART_T *pUART)
Return modem control register/status.
Definition: uart_11xx.h:467
LPC_USART_T::DLL
__IO uint32_t DLL
Definition: uart_11xx.h:52
Chip_UART_SetupFIFOS
STATIC INLINE void Chip_UART_SetupFIFOS(LPC_USART_T *pUART, uint32_t fcr)
Setup the UART FIFOs.
Definition: uart_11xx.h:404
LPC_USART_T::ICR
__IO uint32_t ICR
Definition: uart_11xx.h:73
LPC_USART_T::IIR
__I uint32_t IIR
Definition: uart_11xx.h:64
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)
Definition: uart_11xx.c:97
LPC_USART_T::TER1
__IO uint32_t TER1
Definition: uart_11xx.h:76
STATIC
#define STATIC
Definition: lpc_types.h:140


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