summaryrefslogtreecommitdiff
path: root/nuttx/arch/avr
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2010-10-09 17:39:02 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2010-10-09 17:39:02 +0000
commit1470c38340ea6ffca85f1b100f2fe1f43919685c (patch)
tree2529e56db1f8d87238847d9089cb73960dadac66 /nuttx/arch/avr
parent191c5b0c79eee53dcd2beb8623f89b80b632a2c6 (diff)
downloadpx4-nuttx-1470c38340ea6ffca85f1b100f2fe1f43919685c.tar.gz
px4-nuttx-1470c38340ea6ffca85f1b100f2fe1f43919685c.tar.bz2
px4-nuttx-1470c38340ea6ffca85f1b100f2fe1f43919685c.zip
Finish serial driver
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@2983 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/avr')
-rwxr-xr-xnuttx/arch/avr/include/at91uc3/irq.h165
-rw-r--r--nuttx/arch/avr/src/at91uc3/at91uc3_lowconsole.c2
-rw-r--r--nuttx/arch/avr/src/at91uc3/at91uc3_lowinit.c3
-rwxr-xr-xnuttx/arch/avr/src/at91uc3/at91uc3_memorymap.h10
-rw-r--r--nuttx/arch/avr/src/at91uc3/at91uc3_serial.c164
-rwxr-xr-xnuttx/arch/avr/src/at91uc3/at91uc3_usart.h1
6 files changed, 268 insertions, 77 deletions
diff --git a/nuttx/arch/avr/include/at91uc3/irq.h b/nuttx/arch/avr/include/at91uc3/irq.h
index adb1cc18b..e7555f51e 100755
--- a/nuttx/arch/avr/include/at91uc3/irq.h
+++ b/nuttx/arch/avr/include/at91uc3/irq.h
@@ -53,10 +53,173 @@
****************************************************************************/
/* IRQ numbers */
+/* Events. These exclude:
+ *
+ * - The Reset event which vectors directly either to 0x8000:0000 (uc3a) or
+ * to 0xa000:0000 (uc3b).
+ * - The OCD stop from the OSD system
+ * - Autovectored interrupt requests
+ *
+ * Others vector relative to the contents of the EVBA register.
+ */
+
+#define AVR32_IRQ_UNREC 0 /* EVBA+0x00 Unrecoverable exception */
+#define AVR32_IRQ_TLBMULT 1 /* EVBA+0x04 TLB multiple hit */
+#define AVR32_IRQ_BUSDATA 2 /* EVBA+0x08 Bus error data fetch */
+#define AVR32_IRQ_BUSINST 3 /* EVBA+0x0C Bus error instruction fetch */
+#define AVR32_IRQ_NMI 4 /* EVBA+0x10 NMI */
+#define AVR32_IRQ_INSTADDR 5 /* EVBA+0x14 Instruction Address */
+#define AVR32_IRQ_ITLBMISS 6 /* EVBA+0x50 ITLB Miss */
+#define AVR32_IRQ_ITLBPROT 7 /* EVBA+0x18 ITLB Protection */
+#define AVR32_IRQ_BP 8 /* EVBA+0x1C Breakpoint */
+#define AVR32_IRQ_INVINST 9 /* EVBA+0x20 Illegal Opcode */
+#define AVR32_IRQ_UNIMPINST 10 /* EVBA+0x24 Unimplemented instruction */
+#define AVR32_IRQ_PRIV 11 /* EVBA+0x28 Privilege violation */
+#define AVR32_IRQ_FP 12 /* EVBA+0x2C Floating-point */
+#define AVR32_IRQ_COP 13 /* EVBA+0x30 Coprocessor absent */
+#define AVR32_IRQ_RDDATA 14 /* EVBA+0x34 Data Address (Read) */
+#define AVR32_IRQ_WRDATA 15 /* EVBA+0x38 Data Address (Write) */
+#define AVR32_IRQ_RDDTLB 16 /* EVBA+0x60 DTLB Miss (Read) */
+#define AVR32_IRQ_WRDTLB 17 /* EVBA+0x70 DTLB Miss (Write) */
+#define AVR32_IRQ_RDDTLBPROT 18 /* EVBA+0x3C DTLB Protection (Read) */
+#define AVR32_IRQ_WRDTLBPROT 19 /* EVBA+0x40 DTLB Protection (Write) */
+#define AVR32_IRQ_DLTBMOD 20 /* EVBA+0x44 DTLB Modified */
+#define AVR32_IRQ_SUPER 21 /* EVBA+0x100 Supervisor call */
+#define AVR32_IRQ_NEVENTS 22
+
+/* "The INTC collects interrupt requests from the peripherals, prioritizes
+ * them, and delivers an interrupt request and an autovector to the CPU. The
+ * AVR32 architecture supports 4 priority levels for regular, maskable
+ * interrupts, and a Non-Maskable Interrupt (NMI)."
+ *
+ * "The INTC supports up to 64 groups of interrupts. Each group can have up
+ * to 32 interrupt request lines, these lines are connected to the peripherals.
+ * Each group has an Interrupt Priority Register (IPR) and an Interrupt Request
+ * Register (IRR). The IPRs are used to assign a priority level and an autovector
+ * to each group, and the IRRs are used to identify the active interrupt request
+ * within each group. If a group has only one interrupt request line, an active
+ * interrupt group uniquely identifies the active interrupt request line, and
+ * the corresponding IRR is not needed. The INTC also provides one Interrupt
+ * Cause Register (ICR) per priority level. These registers identify the group
+ * that has a pending interrupt of the corresponding priority level. If several
+ * groups have a pending interrupt of the same level, the group with the lowest
+ * number takes priority."
+ */
+
+/* Group 0 */
+
+#define AVR32_IRQ_GROUP0 22
+#define AVR32_IRQ_UC 22 /* 0 AVR32 UC CPU */
+
+/* Group 1 */
+
+#define AVR32_IRQ_GROUP1 23
+#define AVR32_IRQ_EIC0 23 /* 0 External Interrupt Controller 0 */
+#define AVR32_IRQ_EIC1 24 /* 1 External Interrupt Controller 1 */
+#define AVR32_IRQ_EIC2 25 /* 2 External Interrupt Controller 2 */
+#define AVR32_IRQ_EIC3 26 /* 3 External Interrupt Controller 3 */
+#define AVR32_IRQ_EIC4 27 /* 4 External Interrupt Controller 4 */
+#define AVR32_IRQ_EIC5 28 /* 5 External Interrupt Controller 5 */
+#define AVR32_IRQ_EIC6 29 /* 6 External Interrupt Controller 6 */
+#define AVR32_IRQ_EIC7 30 /* 7 External Interrupt Controller 7 */
+#define AVR32_IRQ_RTC 31 /* 8 Real Time Counter RTC */
+#define AVR32_IRQ_PM 32 /* 9 Power Manager PM */
+
+/* Group 2 */
+
+#define AVR32_IRQ_GROUP2 33
+#define AVR32_IRQ_GPIO0 33 /* 0 General Purpose Input/Output Controller 0 */
+#define AVR32_IRQ_GPIO1 34 /* 1 General Purpose Input/Output Controller 1 */
+#define AVR32_IRQ_GPIO2 35 /* 2 General Purpose Input/Output Controller 2 */
+#define AVR32_IRQ_GPIO3 36 /* 3 General Purpose Input/Output Controller 3 */
+#define AVR32_IRQ_GPIO4 37 /* 4 General Purpose Input/Output Controller 4 */
+#define AVR32_IRQ_GPIO5 38 /* 5 General Purpose Input/Output Controller 5 */
+
+/* Group 3 */
+
+#define AVR32_IRQ_GROUP3 39
+#define AVR32_IRQ_PDCA0 40 /* 0 Peripheral DMA Controller 0 */
+#define AVR32_IRQ_PDCA1 41 /* 1 Peripheral DMA Controller 1 */
+#define AVR32_IRQ_PDCA2 42 /* 2 Peripheral DMA Controller 2 */
+#define AVR32_IRQ_PDCA3 43 /* 3 Peripheral DMA Controller 3 */
+#define AVR32_IRQ_PDCA4 44 /* 4 Peripheral DMA Controller 4 */
+#define AVR32_IRQ_PDCA5 45 /* 5 Peripheral DMA Controller 5 */
+#define AVR32_IRQ_PDCA6 46 /* 6 Peripheral DMA Controller 6 */
+
+/* Group 4 */
+
+#define AVR32_IRQ_GROUP4 47
+#define AVR32_IRQ_FLASHC 47 /* 0 Flash Controller */
+
+/* Group 5 */
+
+#define AVR32_IRQ_GROUP5 48
+#define AVR32_IRQ_USART0 48 /* 0 Universal Synchronous/Asynchronous
+ * Receiver/Transmitter 0 */
+/* Group 6 */
+
+#define AVR32_IRQ_GROUP6 49
+#define AVR32_IRQ_USART1 49 /* 0 Universal Synchronous/Asynchronous
+ * Receiver/Transmitter 1 */
+/* Group 7 */
+
+#define AVR32_IRQ_GROUP7 50
+#define AVR32_IRQ_USART2 50 /* 0 Universal Synchronous/Asynchronous
+ * Receiver/Transmitter 2 */
+
+#define AVR32_IRQ_GROUP8 51
+
+/* Group 9 */
+
+#define AVR32_IRQ_GROUP9 51
+#define AVR32_IRQ_SPI 51 /* 0 Serial Peripheral Interface */
+
+#define AVR32_IRQ_GROUP10 52
+
+/* Group 11 */
+
+#define AVR32_IRQ_GROUP11 52
+#define AVR32_IRQ_TWI 52 /* 0 Two-wire Interface TWI */
+
+/* Group 12 */
+
+#define AVR32_IRQ_GROUP12 53
+#define AVR32_IRQ_PWM 53 /* 0 Pulse Width Modulation Controller */
+
+/* Group 13 */
+
+#define AVR32_IRQ_GROUP13 54
+#define AVR32_IRQ_SSC 54 /* 0 Synchronous Serial Controller */
+
+/* Group 14 */
+
+#define AVR32_IRQ_GROUP14 55
+#define AVR32_IRQ_TC0 55 /* 0 Timer/Counter 0 */
+#define AVR32_IRQ_TC1 56 /* 1 Timer/Counter 1 */
+#define AVR32_IRQ_TC2 57 /* 2 Timer/Counter 2 */
+
+/* Group 15 */
+
+#define AVR32_IRQ_GROUP15 58
+#define AVR32_IRQ_ADC 58 /* 0 Analog to Digital Converter */
+
+#define AVR32_IRQ_GROUP16 59
+
+/* Group 17 */
+
+#define AVR32_IRQ_GROUP17 59
+#define AVR32_IRQ_USBB 59 /* 0 USB 2.0 Interface USBB */
+
+/* Group 18 */
+
+#define AVR32_IRQ_GROUP18 60
+#define AVR32_IRQ_ABDAC 60 /* 0 Audio Bitstream DAC */
+
+#define AVR32_IRQ_GROUP10 61
/* Total number of IRQ numbers */
-#define NR_IRQS 1
+#define NR_IRQS 61
/****************************************************************************
* Public Types
diff --git a/nuttx/arch/avr/src/at91uc3/at91uc3_lowconsole.c b/nuttx/arch/avr/src/at91uc3/at91uc3_lowconsole.c
index 3a05973ff..99345d529 100644
--- a/nuttx/arch/avr/src/at91uc3/at91uc3_lowconsole.c
+++ b/nuttx/arch/avr/src/at91uc3/at91uc3_lowconsole.c
@@ -298,6 +298,7 @@ void usart_configure(uintptr_t usart_base, uint32_t baud, unsigned int parity,
*
******************************************************************************/
+#ifndef CONFIG_USE_EARLYSERIALINIT
void up_consoleinit(void)
{
#ifdef HAVE_SERIAL_CONSOLE
@@ -306,6 +307,7 @@ void up_consoleinit(void)
# warning "Probably not all Implemented"
#endif
}
+#endif
/******************************************************************************
* Name: up_lowputc
diff --git a/nuttx/arch/avr/src/at91uc3/at91uc3_lowinit.c b/nuttx/arch/avr/src/at91uc3/at91uc3_lowinit.c
index 071e86690..3c01fd85a 100644
--- a/nuttx/arch/avr/src/at91uc3/at91uc3_lowinit.c
+++ b/nuttx/arch/avr/src/at91uc3/at91uc3_lowinit.c
@@ -89,13 +89,14 @@ void up_lowinit(void)
/* Initialize a console (probably a serial console) */
+#ifndef CONFIG_USE_EARLYSERIALINIT
up_consoleinit();
+#else
/* Perform early serial initialization (so that we will have debug output
* available as soon as possible).
*/
-#ifdef CONFIG_USE_EARLYSERIALINIT
up_earlyserialinit();
#endif
diff --git a/nuttx/arch/avr/src/at91uc3/at91uc3_memorymap.h b/nuttx/arch/avr/src/at91uc3/at91uc3_memorymap.h
index d5be3ae0f..8095a3a3c 100755
--- a/nuttx/arch/avr/src/at91uc3/at91uc3_memorymap.h
+++ b/nuttx/arch/avr/src/at91uc3/at91uc3_memorymap.h
@@ -60,6 +60,16 @@
#define AVR32_P3_BASE 0xc0000000 /* 512MB translated space, cacheable */
#define AVR32_P4_BASE 0xe0000000 /* 512MB system space, non-cacheable */
+/* Reset vector addess */
+
+#if defined(CONFIG_ARCH_CHIP_AT91UC3A)
+# define AVR32_VECTOR_BASE 0x80000000
+#elif defined(CONFIG_ARCH_CHIP_AT91UC3B)
+# define AVR32_VECTOR_BASE 0xa0000000
+#else
+# warning "Unknown vector base address"
+#endif
+
/* Peripheral Address Map */
#define AVR32_USB_BASE 0xfffe0000 /* USB 2.0 Interface */
diff --git a/nuttx/arch/avr/src/at91uc3/at91uc3_serial.c b/nuttx/arch/avr/src/at91uc3/at91uc3_serial.c
index 9cd550384..e6f7fbb8d 100644
--- a/nuttx/arch/avr/src/at91uc3/at91uc3_serial.c
+++ b/nuttx/arch/avr/src/at91uc3/at91uc3_serial.c
@@ -60,6 +60,7 @@
#include "up_arch.h"
#include "up_internal.h"
#include "os_internal.h"
+#include "at91uc3_internal.h"
/****************************************************************************
* Definitions
@@ -67,10 +68,10 @@
/* Some sanity checks *******************************************************/
-/* Is there a USART enabled? */
+/* Is there at least one USART enabled and configured as a RS-232 device? */
#ifndef HAVE_RS232_DEVICE
-# error "No USARTs enabled as RS232 devices"
+# warning "No USARTs enabled as RS-232 devices"
#endif
/* If we are not using the serial driver for the console, then we still must
@@ -145,11 +146,10 @@ struct up_dev_s
{
uintptr_t usartbase; /* Base address of USART registers */
uint32_t baud; /* Configured baud */
- uint32_t ie; /* Saved interrupt mask bits value */
- uint32_t sr; /* Saved status bits */
+ uint32_t csr; /* Saved channel status register contents */
uint8_t irq; /* IRQ associated with this USART */
uint8_t parity; /* 0=none, 1=odd, 2=even */
- uint8_t bits; /* Number of bits (7 or 8) */
+ uint8_t bits; /* Number of bits (5, 6, 7 or 8) */
bool stopbits2; /* true: Configure with 2 stop bits instead of 1 */
};
@@ -321,32 +321,27 @@ static inline void up_serialout(struct up_dev_s *priv, int offset, uint32_t valu
* Name: up_restoreusartint
****************************************************************************/
-static void up_restoreusartint(struct up_dev_s *priv, uint32_t ie)
+static void up_restoreusartint(struct up_dev_s *priv, uint32_t imr)
{
- uint32_t cr;
+ /* Re-enable interrupts as for each "1" bit in imr */
- /* Save the interrupt mask */
-
- priv->ie = ie;
-
- /* And restore the interrupt state (see the interrupt enable/usage table above) */
-#warning "Not Implemented"
+ up_serialout(priv, AVR32_USART_IER_OFFSET, imr);
}
/****************************************************************************
* Name: up_disableusartint
****************************************************************************/
-static inline void up_disableusartint(struct up_dev_s *priv, uint16_t *ie)
+static inline void up_disableusartint(struct up_dev_s *priv, uint32_t *imr)
{
- if (ie)
+ if (imr)
{
-#warning "Not Implemented"
+ *imr = up_serialin(priv, AVR32_USART_IDR_OFFSET);
}
/* Disable all interrupts */
- up_restoreusartint(priv, 0);
+ up_serialout(priv, AVR32_USART_IDR_OFFSET, USART_INT_ALL);
}
/****************************************************************************
@@ -360,18 +355,15 @@ static inline void up_disableusartint(struct up_dev_s *priv, uint16_t *ie)
static int up_setup(struct uart_dev_s *dev)
{
+#ifndef CONFIG_SUPPRESS_UART_CONFIG
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
-#ifdef CONFIG_SUPPRESS_UART_CONFIG
/* Configure the USART as an RS-232 UART */
usart_configure(priv->usartbase, priv->baud, priv->parity,
priv->bits, priv->stopbits2);
#endif
- /* Initialize the IMR shadow register */
-
- priv->ie = up_serialout(priv, AVR32_USART_IMR_OFFSET, regval);;
return OK;
}
@@ -460,6 +452,7 @@ static int up_interrupt(int irq, void *context)
{
struct uart_dev_s *dev = NULL;
struct up_dev_s *priv;
+ uint32_t csr;
int passes;
bool handled;
@@ -488,6 +481,7 @@ static int up_interrupt(int irq, void *context)
PANIC(OSERR_INTERNAL);
}
priv = (struct up_dev_s*)dev->priv;
+ DEBUGASSERT(priv);
/* Loop until there are no characters to be transferred or,
* until we have been looping for a long time.
@@ -498,12 +492,14 @@ static int up_interrupt(int irq, void *context)
{
handled = false;
- /* Get the masked USART status and clear the pending interrupts. */
-#warning "Not Implemented"
+ /* Get the USART channel status register contents. */
+
+ csr = up_serialin(priv, AVR32_USART_CSR_OFFSET);
+ priv->csr = csr;
/* Handle incoming, receive bytes (with or without timeout) */
-#warning "Not Implemented"
- if (false)
+
+ if ((csr & (USART_CSR_RXRDY|USART_CSR_TIMEOUT)) != 0)
{
/* Received data ready... process incoming bytes */
@@ -512,8 +508,8 @@ static int up_interrupt(int irq, void *context)
}
/* Handle outgoing, transmit bytes */
-#warning "Not Implemented"
- if (false)
+
+ if ((csr & USART_CSR_TXRDY) != 0)
{
/* Transmit data regiser empty ... process outgoing bytes */
@@ -534,28 +530,23 @@ static int up_interrupt(int irq, void *context)
static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
{
- struct inode *inode = filep->f_inode;
- struct uart_dev_s *dev = inode->i_private;
-#ifdef CONFIG_USART_BREAKS
- struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
-#endif
- int ret = OK;
+#if 0 /* Reserved for future growth */
+ struct inode *inode;
+ struct uart_dev_s *dev;
+ struct up_dev_s *priv;
+ int ret = OK;
+
+ DEBUGASSERT(filep, filep->f_inode);
+ inode = filep->f_inode;
+ dev = inode->i_private;
+
+ DEBUGASSERT(dev, dev->priv)
+ priv = (struct up_dev_s*)dev->priv;
switch (cmd)
{
- case TIOCSERGSTRUCT:
- {
- struct up_dev_s *user = (struct up_dev_s*)arg;
- if (!user)
- {
- ret = -EINVAL;
- }
- else
- {
- memcpy(user, dev, sizeof(struct up_dev_s));
- }
- }
- break;
+ case xxx: /* Add commands here */
+ break;
default:
ret = -ENOTTY;
@@ -563,6 +554,9 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
}
return ret;
+#else
+ return -ENOTTY;
+#endif
}
/****************************************************************************
@@ -578,18 +572,25 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
static int up_receive(struct uart_dev_s *dev, uint32_t *status)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
- uint32_t dr;
+ uint32_t rhr;
+
+ /* Get the Rx byte. The USART Rx interrupt flag is cleared by side effect
+ * when reading the received character.
+ */
- /* Get the Rx byte */
-#warning "Not Implemented"
+ rhr = up_serialin(priv, AVR32_USART_RHR_OFFSET);
- /* Get the Rx byte plux error information. Return those in status */
-#warning "Not Implemented"
- priv->sr = 0;
+ /* Return status information */
+
+ if (status)
+ {
+ *status = priv->csr;
+ }
+ priv->csr = 0;
/* Then return the actual received byte */
- return dr & 0xff;
+ return rhr & USART_RHR_RXCHR_MASK;
}
/****************************************************************************
@@ -603,9 +604,7 @@ static int up_receive(struct uart_dev_s *dev, uint32_t *status)
static void up_rxint(struct uart_dev_s *dev, bool enable)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
- uint32_t ie;
-
- ie = priv->ie;
+
if (enable)
{
/* Receive an interrupt when their is anything in the Rx data register (or an Rx
@@ -613,21 +612,22 @@ static void up_rxint(struct uart_dev_s *dev, bool enable)
*/
#ifndef CONFIG_SUPPRESS_SERIAL_INTS
-#ifdef CONFIG_USART_ERRINTS
-#warning "Not Implemented"
-#else
-#warning "Not Implemented"
-#endif
+# ifdef CONFIG_USART_ERRINTS
+ up_serialout(priv, AVR32_USART_IER_OFFSET,
+ USART_INT_RXRDY|USART_INT_TIMEOUT|
+ USART_INT_OVRE|USART_INT_FRAME|USART_INT_PARE);
+# else
+ up_serialout(priv, AVR32_USART_IER_OFFSET,
+ USART_INT_RXRDY|USART_INT_TIMEOUT);
+# endif
#endif
}
else
{
-#warning "Not Implemented"
+ up_serialout(priv, AVR32_USART_IDR_OFFSET,
+ USART_INT_RXRDY|USART_INT_TIMEOUT|
+ USART_INT_OVRE|USART_INT_FRAME|USART_INT_PARE);
}
-
- /* Then set the new interrupt state */
-
- up_restoreusartint(priv, ie);
}
/****************************************************************************
@@ -641,21 +641,28 @@ static void up_rxint(struct uart_dev_s *dev, bool enable)
static bool up_rxavailable(struct uart_dev_s *dev)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
-#warning "Not Implemented"
+ uint32_t regval;
+
+ /* Read the channel status register and check if character is available to
+ * be read from the RHR.
+ */
+
+ regval = up_serialin(priv, AVR32_USART_CSR_OFFSET);
+ return (regval & USART_CSR_RXRDY) != 0;
}
/****************************************************************************
* Name: up_send
*
* Description:
- * This method will send one byte on the USART
+ * This method will send one byte on the USART.
*
****************************************************************************/
static void up_send(struct uart_dev_s *dev, int ch)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
-#warning "Not Implemented"
+ up_serialout(priv, AVR32_USART_THR_OFFSET, (uint32_t)ch);
}
/****************************************************************************
@@ -677,7 +684,7 @@ static void up_txint(struct uart_dev_s *dev, bool enable)
/* Set to receive an interrupt when the TX data register is empty */
#ifndef CONFIG_SUPPRESS_SERIAL_INTS
-#warning "Not Implemented"
+ up_serialout(priv, AVR32_USART_IER_OFFSET, USART_INT_TXRDY);
/* Fake a TX interrupt here by just calling uart_xmitchars() with
* interrupts disabled (note this may recurse).
@@ -690,7 +697,7 @@ static void up_txint(struct uart_dev_s *dev, bool enable)
{
/* Disable the TX interrupt */
-#warning "Not Implemented"
+ up_serialout(priv, AVR32_USART_IDR_OFFSET, USART_INT_TXRDY);
}
irqrestore(flags);
}
@@ -706,7 +713,14 @@ static void up_txint(struct uart_dev_s *dev, bool enable)
static bool up_txready(struct uart_dev_s *dev)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
-#warning "Not Implemented"
+ uint32_t regval;
+
+ /* Read the channel status register and check if THR is ready to accept
+ * another character.
+ */
+
+ regval = up_serialin(priv, AVR32_USART_CSR_OFFSET);
+ return (regval & USART_CSR_TXRDY) != 0;
}
/****************************************************************************
@@ -783,9 +797,9 @@ int up_putc(int ch)
{
#ifdef HAVE_SERIAL_CONSOLE
struct up_dev_s *priv = (struct up_dev_s*)CONSOLE_DEV.priv;
- uint16_t ie;
+ uint32_t imr;
- up_disableusartint(priv, &ie);
+ up_disableusartint(priv, &imr);
/* Check for LF */
@@ -797,7 +811,7 @@ int up_putc(int ch)
}
up_lowputc(ch);
- up_restoreusartint(priv, ie);
+ up_restoreusartint(priv, imr);
#endif
return ch;
}
diff --git a/nuttx/arch/avr/src/at91uc3/at91uc3_usart.h b/nuttx/arch/avr/src/at91uc3/at91uc3_usart.h
index 846d5c833..f06eb0b3a 100755
--- a/nuttx/arch/avr/src/at91uc3/at91uc3_usart.h
+++ b/nuttx/arch/avr/src/at91uc3/at91uc3_usart.h
@@ -224,6 +224,7 @@
#define USART_INT_CTSIC (1 << 19) /* Bit 19: */
#define USART_INT_MANE (1 << 20) /* Bit 20: */
#define USART_INT_MANEA (1 << 24) /* Bit 24: */
+#define USART_INT_ALL 0x011f37e7
/* CSR Register Bit-field Definitions */