summaryrefslogtreecommitdiff
path: root/nuttx/arch/avr/src/at32uc3
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2010-10-30 00:40:53 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2010-10-30 00:40:53 +0000
commitfc44796aa0ce534591ab5f19fad282f34ff1ab44 (patch)
tree9cdab5d8ef446adb1d3034888d31112208c0dafa /nuttx/arch/avr/src/at32uc3
parent39f492cc53cc5d6b2e744ee68d9f6bd724f933c2 (diff)
downloadpx4-nuttx-fc44796aa0ce534591ab5f19fad282f34ff1ab44.tar.gz
px4-nuttx-fc44796aa0ce534591ab5f19fad282f34ff1ab44.tar.bz2
px4-nuttx-fc44796aa0ce534591ab5f19fad282f34ff1ab44.zip
Fix big-time naming error -- what was I thinking?
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3058 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/avr/src/at32uc3')
-rw-r--r--nuttx/arch/avr/src/at32uc3/Make.defs64
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_abdac.h101
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_adc.h195
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_clkinit.c501
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_config.h176
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_eic.h133
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_flashc.h229
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_gpio.c296
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_gpio.h465
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_gpioirq.c428
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_hmatrix.h314
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_intc.h98
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_internal.h344
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_irq.c333
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_lowconsole.c374
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_lowinit.c107
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_memorymap.h114
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_pdca.h277
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_pinmux.h71
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_pm.h335
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_pwm.h222
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_rtc.h112
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_serial.c839
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_spi.h166
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_ssc.h267
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_tc.h372
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_timerisr.c190
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_twi.h161
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_usart.h339
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_usbb.h1098
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_wdt.h87
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3a_pinmux.h64
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3b_pinmux.h263
-rw-r--r--nuttx/arch/avr/src/at32uc3/chip.h223
34 files changed, 9358 insertions, 0 deletions
diff --git a/nuttx/arch/avr/src/at32uc3/Make.defs b/nuttx/arch/avr/src/at32uc3/Make.defs
new file mode 100644
index 000000000..94dc5d2dc
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/Make.defs
@@ -0,0 +1,64 @@
+############################################################################
+# arch/avr/src/at32uc3/Make.defs
+#
+# Copyright (C) 2010 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+# The start-up, "head", file
+
+HEAD_ASRC = up_nommuhead.S
+
+# Common AVR/AVR32 files
+
+CMN_ASRCS = up_exceptions.S up_fullcontextrestore.S up_switchcontext.S
+CMN_CSRCS = up_assert.c up_allocateheap.c up_blocktask.c up_copystate.c \
+ up_createstack.c up_mdelay.c up_udelay.c up_exit.c up_idle.c \
+ up_initialize.c up_initialstate.c up_interruptcontext.c \
+ up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c \
+ up_releasepending.c up_releasestack.c up_reprioritizertr.c \
+ up_schedulesigaction.c up_sigdeliver.c up_unblocktask.c \
+ up_usestack.c up_doirq.c
+
+# Required AT32UC3 files
+
+CHIP_ASRCS =
+CHIP_CSRCS = at32uc3_clkinit.c at32uc3_gpio.c at32uc3_irq.c \
+ at32uc3_lowconsole.c at32uc3_lowinit.c at32uc3_serial.c \
+ at32uc3_timerisr.c
+
+# Configuration-dependent AT32UC3 files
+
+ifeq ($(CONFIG_AVR32_GPIOIRQ),y)
+CHIP_CSRCS += at32uc3_gpioirq.c
+endif
+
+
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_abdac.h b/nuttx/arch/avr/src/at32uc3/at32uc3_abdac.h
new file mode 100644
index 000000000..f71229f89
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_abdac.h
@@ -0,0 +1,101 @@
+/************************************************************************************
+ * arch/avr/src/at32uc3/at32uc3_abdac.h
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_AVR_SRC_AT32UC3_AT32UC3_ABDAC_H
+#define __ARCH_AVR_SRC_AT32UC3_AT32UC3_ABDAC_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+
+#define AVR32_ABDAC_SDR_OFFSET 0x00 /* Sample Data Register */
+#define AVR32_ABDAC_CR_OFFSET 0x08 /* Control Register */
+#define AVR32_ABDAC_IMR_OFFSET 0x0c /* Interrupt Mask Register */
+#define AVR32_ABDAC_IER_OFFSET 0x10 /* Interrupt Enable Register */
+#define AVR32_ABDAC_IDR_OFFSET 0x14 /* Interrupt Disable Register */
+#define AVR32_ABDAC_ICR_OFFSET 0x18 /* Interrupt Clear Register */
+#define AVR32_ABDAC_ISR_OFFSET 0x1c /* Interrupt Status Register */
+
+/* Register Addresses ***************************************************************/
+
+#define AVR32_ABDAC_SDR (AVR32_ABDAC_BASE+AVR32_ABDAC_SDR_OFFSET)
+#define AVR32_ABDAC_CR (AVR32_ABDAC_BASE+AVR32_ABDAC_CR_OFFSET)
+#define AVR32_ABDAC_IMR (AVR32_ABDAC_BASE+AVR32_ABDAC_IMR_OFFSET)
+#define AVR32_ABDAC_IER (AVR32_ABDAC_BASE+AVR32_ABDAC_IER_OFFSET)
+#define AVR32_ABDAC_IDR (AVR32_ABDAC_BASE+AVR32_ABDAC_IDR_OFFSET)
+#define AVR32_ABDAC_ICR (AVR32_ABDAC_BASE+AVR32_ABDAC_ICR_OFFSET)
+#define AVR32_ABDAC_ISR (AVR32_ABDAC_BASE+AVR32_ABDAC_ISR_OFFSET)
+
+/* Register Bit-field Definitions ***************************************************/
+
+/* Sample Data Register Bit-field Definitions */
+/* This register contains a 32-bit data and, hence, has no bit-fiels */
+
+/* Control Register Bit-field Definitions */
+
+#define ABDAC_CR_SWAP (1 << 30) /* Bit 30: Swap Channels */
+#define ABDAC_CR_EN (1 << 31) /* Bit 31: Enable Audio Bitstream DAC */
+
+/* Interrupt Mask Register Bit-field Definitions */
+/* Interrupt Enable Register Bit-field Definitions */
+/* Interrupt Disable Register Bit-field Definitions */
+/* Interrupt Clear Register Bit-field Definitions */
+/* Interrupt Status Register Bit-field Definitions */
+
+#define ABDAC_INT_UNDERRUN (1 << 28) /* Bit 28: Underrun Interrupt Status */
+#define ABDAC_INT_TXREADY (1 << 29) /* Bit 29 TX Ready Interrupt Status */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_AVR_SRC_AT32UC3_AT32UC3_ABDAC_H */
+
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_adc.h b/nuttx/arch/avr/src/at32uc3/at32uc3_adc.h
new file mode 100644
index 000000000..7695e6e65
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_adc.h
@@ -0,0 +1,195 @@
+/************************************************************************************
+ * arch/avr/src/at32uc3/at32uc3_adc.h
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_AVR_SRC_AT32UC3_AT32UC3_ADC_H
+#define __ARCH_AVR_SRC_AT32UC3_AT32UC3_ADC_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+
+#define AVR32_ADC_CR_OFFSET 0x000 /* Control Register */
+#define AVR32_ADC_MR_OFFSET 0x004 /* Mode Register */
+#define AVR32_ADC_CHER_OFFSET 0x010 /* Channel Enable Register */
+#define AVR32_ADC_CHDR_OFFSET 0x014 /* Channel Disable Register */
+#define AVR32_ADC_CHSR_OFFSET 0x018 /* Channel Status Register */
+#define AVR32_ADC_SR_OFFSET 0x01c /* Status Register */
+#define AVR32_ADC_LCDR_OFFSET 0x020 /* Last Converted Data Register */
+#define AVR32_ADC_IER_OFFSET 0x024 /* Interrupt Enable Register */
+#define AVR32_ADC_IDR_OFFSET 0x028 /* Interrupt Disable Register */
+#define AVR32_ADC_IMR_OFFSET 0x02c /* Interrupt Mask Register */
+#define AVR32_ADC_CDR_OFFSET(n) (0x030+((n)<<2))
+#define AVR32_ADC_CDR0_OFFSET 0x030 /* Channel Data Register 0 */
+#define AVR32_ADC_CDR1_OFFSET 0x034 /* Channel Data Register 1 */
+#define AVR32_ADC_CDR2_OFFSET 0x038 /* Channel Data Register 2 */
+#define AVR32_ADC_CDR3_OFFSET 0x03c /* Channel Data Register 3 */
+#define AVR32_ADC_CDR4_OFFSET 0x040 /* Channel Data Register 4 */
+#define AVR32_ADC_CDR5_OFFSET 0x044 /* Channel Data Register 5 */
+#define AVR32_ADC_CDR6_OFFSET 0x048 /* Channel Data Register 6 */
+#define AVR32_ADC_CDR7_OFFSET 0x04c /* Channel Data Register 7 */
+#define AVR32_ADC_VERSION_OFFSET 0x0fc /* Version Register */
+
+/* Register Addresses ***************************************************************/
+
+#define AVR32_ADC_CR (AVR32_ADC_BASE+AVR32_ADC_CR_OFFSET)
+#define AVR32_ADC_MR (AVR32_ADC_BASE+AVR32_ADC_MR_OFFSET)
+#define AVR32_ADC_CHER (AVR32_ADC_BASE+AVR32_ADC_CHER_OFFSET)
+#define AVR32_ADC_CHDR (AVR32_ADC_BASE+AVR32_ADC_CHDR_OFFSET)
+#define AVR32_ADC_CHSR (AVR32_ADC_BASE+AVR32_ADC_CHSR_OFFSET)
+#define AVR32_ADC_SR (AVR32_ADC_BASE+AVR32_ADC_SR_OFFSET)
+#define AVR32_ADC_LCDR (AVR32_ADC_BASE+AVR32_ADC_LCDR_OFFSET)
+#define AVR32_ADC_IER (AVR32_ADC_BASE+AVR32_ADC_IER_OFFSET)
+#define AVR32_ADC_IDR (AVR32_ADC_BASE+AVR32_ADC_IDR_OFFSET)
+#define AVR32_ADC_IMR (AVR32_ADC_BASE+AVR32_ADC_IMR_OFFSET)
+#define AVR32_ADC_CDR(n) (AVR32_ADC_BASE+AVR32_ADC_CDR_OFFSET(n))
+#define AVR32_ADC_CDR0 (AVR32_ADC_BASE+AVR32_ADC_CDR0_OFFSET)
+#define AVR32_ADC_CDR1 (AVR32_ADC_BASE+AVR32_ADC_CDR1_OFFSET)
+#define AVR32_ADC_CDR2 (AVR32_ADC_BASE+AVR32_ADC_CDR2_OFFSET)
+#define AVR32_ADC_CDR3 (AVR32_ADC_BASE+AVR32_ADC_CDR3_OFFSET)
+#define AVR32_ADC_CDR4 (AVR32_ADC_BASE+AVR32_ADC_CDR4_OFFSET)
+#define AVR32_ADC_CDR5 (AVR32_ADC_BASE+AVR32_ADC_CDR5_OFFSET)
+#define AVR32_ADC_CDR6 (AVR32_ADC_BASE+AVR32_ADC_CDR6_OFFSET)
+#define AVR32_ADC_CDR7 (AVR32_ADC_BASE+AVR32_ADC_CDR7_OFFSET)
+#define AVR32_ADC_VERSION (AVR32_ADC_BASE+AVR32_ADC_VERSION_OFFSET)
+
+/* Register Bit-field Definitions ***************************************************/
+
+/* Control Register Bit-field Definitions */
+
+#define ADC_CR_SWRST (1 << 0) /* Bit 0: Software Reset */
+#define ADC_CR_START (1 << 1) /* Bit 1: Start Conversion */
+
+/* Mode Register Bit-field Definitions */
+
+#define ADC_MR_TRGEN (1 << 0) /* Bit 0: Trigger Enable */
+#define ADC_MR_TRGSEL_SHIFT (1) /* Bits 1-3: Trigger Selection */
+#define ADC_MR_TRGSEL_MASK (7 << ADC_MR_TRGSEL_SHIFT)
+# define ADC_MR_TRGSEL_TRIG(n) ((n) << ADC_MR_TRGSEL_SHIFT) /* Internal trigger n */
+# define ADC_MR_TRGSEL_TRIG0 (0 << ADC_MR_TRGSEL_SHIFT) /* Internal trigger 0 */
+# define ADC_MR_TRGSEL_TRIG1 (1 << ADC_MR_TRGSEL_SHIFT) /* Internal trigger 1 */
+# define ADC_MR_TRGSEL_TRIG2 (2 << ADC_MR_TRGSEL_SHIFT) /* Internal trigger 2 */
+# define ADC_MR_TRGSEL_TRIG3 (3 << ADC_MR_TRGSEL_SHIFT) /* Internal trigger 3 */
+# define ADC_MR_TRGSEL_TRIG4 (4 << ADC_MR_TRGSEL_SHIFT) /* Internal trigger 4 */
+# define ADC_MR_TRGSEL_TRIG5 (5 << ADC_MR_TRGSEL_SHIFT) /* Internal trigger 5 */
+# define ADC_MR_TRGSEL_TRIG6 (6 << ADC_MR_TRGSEL_SHIFT) /* Internal trigger 6 */
+# define ADC_MR_TRGSEL_EXT (7 << ADC_MR_TRGSEL_SHIFT) /* External trigger */
+#define ADC_MR_LOWRES (1 << 4) /* Bit 4: Resolution */
+#define ADC_MR_SLEEP (1 << 5) /* Bit 5: Sleep Mode */
+#define ADC_MR_PRESCAL_SHIFT (8) /* Bits 8-15: Prescaler Rate Selection */
+#define ADC_MR_PRESCAL_MASK (0xff << ADC_MR_PRESCAL_SHIFT)
+#define ADC_MR_STARTUP_SHIFT (16) /* Bits 16-22: Start Up Time */
+#define ADC_MR_STARTUP_MASK (0x7f << ADC_MR_STARTUP_SHIFT)
+#define ADC_MR_SHTIM_SHIFT (24) /* Bits 24-27 Sample & Hold Time */
+#define ADC_MR_SHTIM_MASK (15 << ADC_MR_SHTIM_SHIFT)
+
+/* Channel Enable Register Bit-field Definitions */
+/* Channel Disable Register Bit-field Definitions */
+/* Channel Status Register Bit-field Definitions */
+
+#define ADC_CHAN(n) (1 << (n))
+#define ADC_CHAN0 (1 << 0)
+#define ADC_CHAN1 (1 << 1)
+#define ADC_CHAN2 (1 << 2)
+#define ADC_CHAN3 (1 << 3)
+#define ADC_CHAN4 (1 << 4)
+#define ADC_CHAN5 (1 << 5)
+#define ADC_CHAN6 (1 << 6)
+#define ADC_CHAN7 (1 << 7)
+
+/* Status Register Bit-field Definitions */
+/* Interrupt Enable Register Bit-field Definitions */
+/* Interrupt Disable Register Bit-field Definitions */
+/* Interrupt Mask Register Bit-field Definitions */
+
+#define ADC_INT_EOC(n) (1 << (n))
+#define ADC_INT_EOC0 (1 << 0) /* Bit 0: End of Conversion 0 */
+#define ADC_INT_EOC1 (1 << 1) /* Bit 1: End of Conversion 1 */
+#define ADC_INT_EOC2 (1 << 2) /* Bit 2: End of Conversion 2 */
+#define ADC_INT_EOC3 (1 << 3) /* Bit 3: End of Conversion 3 */
+#define ADC_INT_EOC4 (1 << 4) /* Bit 4: End of Conversion 4 */
+#define ADC_INT_EOC5 (1 << 5) /* Bit 5: End of Conversion 5 */
+#define ADC_INT_EOC6 (1 << 6) /* Bit 6: End of Conversion 6 */
+#define ADC_INT_EOC7 (1 << 7) /* Bit 7: End of Conversion 7 */
+#define ADC_INT_OVRE(n) (1 << ((n)+8))
+#define ADC_INT_OVRE0 (1 << 8) /* Bit 8: Overrun Error 0 */
+#define ADC_INT_OVRE1 (1 << 9) /* Bit 9: Overrun Error 1 */
+#define ADC_INT_OVRE2 (1 << 10) /* Bit 10: Overrun Error 2 */
+#define ADC_INT_OVRE3 (1 << 11) /* Bit 11: Overrun Error 3 */
+#define ADC_INT_OVRE4 (1 << 12) /* Bit 12: Overrun Error 4 */
+#define ADC_INT_OVRE5 (1 << 13) /* Bit 13: Overrun Error 5 */
+#define ADC_INT_OVRE6 (1 << 14) /* Bit 14: Overrun Error 6 */
+#define ADC_INT_OVRE7 (1 << 15) /* Bit 15: Overrun Error 7 */
+#define ADC_INT_DRDY (1 << 16) /* Bit 16: Data Ready */
+#define ADC_INT_GOVRE (1 << 17) /* Bit 17: General Overrun Error */
+#define ADC_INT_ENDRX (1 << 18) /* Bit 18: End of RX Buffer */
+#define ADC_INT_RXBUFF (1 << 19) /* Bit 19: RX Buffer Full */
+
+/* Last Converted Data Register Bit-field Definitions */
+
+#define ADC_LCDR_MASK (0x3ff)
+
+/* Channel Data Registers 0-7 Bit-field Definitions */
+
+#define ADC_CDR_MASK (0x3ff)
+
+/* Version Register Bit-field Definitions */
+
+#define ADC_VERSION_SHIFT (0) /* Bits 0-11: Version Number */
+#define ADC_VERSION_MASK (0xfff << ADC_VERSION_SHIFT)
+#define ADC_VERSION_VARIANT_SHIFT (16) /* Bits 16-19: Variant Number */
+#define ADC_VERSION_VARIANT_MASK (15 << ADC_VERSION_VARIANT_SHIFT)
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_AVR_SRC_AT32UC3_AT32UC3_ADC_H */
+
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_clkinit.c b/nuttx/arch/avr/src/at32uc3/at32uc3_clkinit.c
new file mode 100644
index 000000000..3f2c7c096
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_clkinit.c
@@ -0,0 +1,501 @@
+/**************************************************************************
+ * arch/avr/src/at32uc3/at32uc3_clkinit.c
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ **************************************************************************/
+
+/**************************************************************************
+ * Included Files
+ **************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+
+#include "at32uc3_config.h"
+#include "up_internal.h"
+#include "at32uc3_internal.h"
+#include "at32uc3_pm.h"
+#include "at32uc3_flashc.h"
+
+/**************************************************************************
+ * Private Definitions
+ **************************************************************************/
+
+#if defined(AVR32_CLOCK_OSC0) || \
+ (defined (AVR32_CLOCK_PLL0) && defined(AVR32_CLOCK_PLL0_OSC0)) || \
+ (defined (AVR32_CLOCK_PLL0) && defined(AVR32_CLOCK_PLL0_OSC0))
+# define NEED_OSC0
+#endif
+
+#if defined(AVR32_CLOCK_OSC1) || \
+ (defined (AVR32_CLOCK_PLL0) && defined(AVR32_CLOCK_PLL0_OSC1)) || \
+ (defined (AVR32_CLOCK_PLL1) && defined(AVR32_CLOCK_PLL0_OSC1))
+# define NEED_OSC1
+#endif
+
+/**************************************************************************
+ * Private Types
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Function Prototypes
+ **************************************************************************/
+
+/**************************************************************************
+ * Global Variables
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Variables
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Functions
+ **************************************************************************/
+
+/**************************************************************************
+ * Name: up_enableosc32
+ *
+ * Description:
+ * Initialiaze the 32KHz oscillaor. This oscillaor is used by the RTC
+ * logic to provide the sysem timer.
+ *
+ **************************************************************************/
+
+static inline void up_enableosc32(void)
+{
+ uint32_t regval;
+
+ /* Select the 32KHz oscillator crystal */
+
+ regval = getreg32(AVR32_PM_OSCCTRL32);
+ regval &= ~PM_OSCCTRL32_MODE_MASK;
+ regval |= PM_OSCCTRL32_MODE_XTAL;
+ putreg32(regval, AVR32_PM_OSCCTRL32);
+
+ /* Enable the 32-kHz clock */
+
+ regval = getreg32(AVR32_PM_OSCCTRL32);
+ regval &= ~PM_OSCCTRL_STARTUP_MASK;
+ regval |= PM_OSCCTRL32_EN|(AVR32_OSC32STARTUP << PM_OSCCTRL_STARTUP_SHIFT);
+ putreg32(regval, AVR32_PM_OSCCTRL32);
+}
+
+/**************************************************************************
+ * Name: up_enableosc0
+ *
+ * Description:
+ * Initialiaze OSC0 settings per the definitions in the board.h file.
+ *
+ **************************************************************************/
+
+#ifdef NEED_OSC0
+static inline void up_enableosc0(void)
+{
+ uint32_t regval;
+
+ /* Enable OSC0 in the correct crystal mode by setting the mode value in OSCCTRL0 */
+
+ regval = getreg32(AVR32_PM_OSCCTRL0);
+ regval &= ~PM_OSCCTRL_MODE_MASK;
+#if AVR32_FOSC0 < 900000
+ regval |= PM_OSCCTRL_MODE_XTALp9; /* Crystal XIN 0.4-0.9MHz */
+#elif AVR32_FOSC0 < 3000000
+ regval |= PM_OSCCTRL_MODE_XTAL3; /* Crystal XIN 0.9-3.0MHz */
+#elif AVR32_FOSC0 < 8000000
+ regval |= PM_OSCCTRL_MODE_XTAL8; /* Crystal XIN 3.0-8.0MHz */
+#else
+ regval |= PM_OSCCTRL_MODE_XTALHI; /* Crystal XIN above 8.0MHz */
+#endif
+ putreg32(regval, AVR32_PM_OSCCTRL0);
+
+ /* Enable OSC0 using the startup time provided in board.h. This startup time
+ * is critical and depends on the characteristics of the crystal.
+ */
+
+ regval = getreg32(AVR32_PM_OSCCTRL0);
+ regval &= ~PM_OSCCTRL_STARTUP_MASK;
+ regval |= (AVR32_OSC0STARTUP << PM_OSCCTRL_STARTUP_SHIFT);
+ putreg32(regval, AVR32_PM_OSCCTRL0);
+
+ /* Enable OSC0 */
+
+ regval = getreg32(AVR32_PM_MCCTRL);
+ regval |= PM_MCCTRL_OSC0EN;
+ putreg32(regval, AVR32_PM_MCCTRL);
+
+ /* Wait for OSC0 to be ready */
+
+ while ((getreg32(AVR32_PM_POSCSR) & PM_POSCSR_OSC0RDY) == 0);
+}
+#endif
+
+/**************************************************************************
+ * Name: up_enableosc1
+ *
+ * Description:
+ * Initialiaze OSC0 settings per the definitions in the board.h file.
+ *
+ **************************************************************************/
+
+#ifdef NEED_OSC1
+static inline void up_enableosc1(void)
+{
+ uint32_t regval;
+
+ /* Enable OSC1 in the correct crystal mode by setting the mode value in OSCCTRL1 */
+
+ regval = getreg32(AVR32_PM_OSCCTRL1);
+ regval &= ~PM_OSCCTRL_MODE_MASK;
+#if AVR32_FOSC1 < 900000
+ regval |= PM_OSCCTRL_MODE_XTALp9; /* Crystal XIN 0.4-0.9MHz */
+#elif AVR32_FOSC1 < 3000000
+ regval |= PM_OSCCTRL_MODE_XTAL3; /* Crystal XIN 0.9-3.0MHz */
+#elif AVR32_FOSC1 < 8000000
+ regval |= PM_OSCCTRL_MODE_XTAL8; /* Crystal XIN 3.0-8.0MHz */
+#else
+ regval |= PM_OSCCTRL_MODE_XTALHI; /* Crystal XIN above 8.0MHz */
+#endif
+ putreg32(regval, AVR32_PM_OSCCTRL1);
+
+ /* Enable OSC1 using the startup time provided in board.h. This startup time
+ * is critical and depends on the characteristics of the crystal.
+ */
+
+ regval = getreg32(AVR32_PM_OSCCTRL1);
+ regval &= ~PM_OSCCTRL_STARTUP_MASK;
+ regval |= (AVR32_OSC1STARTUP << PM_OSCCTRL_STARTUP_SHIFT);
+ putreg32(regval, AVR32_PM_OSCCTRL1);
+
+ /* Enable OSC1 */
+
+ regval = getreg32(AVR32_PM_MCCTRL);
+ regval |= PM_MCCTRL_OSC1EN;
+ putreg32(regval, AVR32_PM_MCCTRL);
+
+ /* Wait for OSC1 to be ready */
+
+ while ((getreg32(AVR32_PM_POSCSR) & PM_POSCSR_OSC1RDY) == 0);
+}
+#endif
+
+/**************************************************************************
+ * Name: up_enablepll0
+ *
+ * Description:
+ * Initialiaze PLL0 settings per the definitions in the board.h file.
+ *
+ **************************************************************************/
+
+#ifdef AVR32_CLOCK_PLL0
+static inline void up_enableosc1(void)
+{
+ /* Setup PLL0 */
+
+ regval = (AVR32_PLL0_DIV << PM_PLL_PLLDIV_SHIFT) | (AVR32_PLL0_MUL << PM_PLL_PLLMUL_SHIFT) | (16 << PM_PLL_PLLCOUNT_SHIFT)
+
+ /* Select PLL0/1 oscillator */
+
+#if AVR32_CLOCK_PLL_OSC1
+ regval |= PM_PLL_PLLOSC;
+#endif
+
+ putreg32(regval, AVR32_PM_PLL0);
+
+ /* Set PLL0 options */
+
+ regval = getreg32(AVR32_PM_PLL0);
+ regval &= ~PM_PLL_PLLOPT_MASK
+#if AVR32_PLL0_FREQ < 160000000
+ regval |= PM_PLL_PLLOPT_VCO;
+#endif
+#if AVR32_PLL0_DIV2 != 0
+ regval |= PM_PLL_PLLOPT_XTRADIV;
+#endif
+#if AVR32_PLL0_WBWM != 0
+ regval |= PM_PLL_PLLOPT_WBWDIS;
+#endif
+ putreg32(regval, AVR32_PM_PLL0)
+
+ /* Enable PLL0 */
+
+ regval = getreg32(AVR32_PM_PLL0);
+ regval |= PM_PLL_PLLEN;
+ putreg32(regval, AVR32_PM_PLL0)
+
+ /* Wait for PLL0 locked. */
+
+ while ((getreg32(AVR32_PM_POSCSR) & PM_POSCSR_LOCK0) == 0);
+}
+#endif
+
+/**************************************************************************
+ * Name: up_enablepll1
+ *
+ * Description:
+ * Initialiaze PLL1 settings per the definitions in the board.h file.
+ *
+ **************************************************************************/
+
+#ifdef AVR32_CLOCK_PLL1
+static inline void up_enableosc1(void)
+{
+ /* Setup PLL1 */
+
+ regval = (AVR32_PLL1_DIV << PM_PLL_PLLDIV_SHIFT) | (AVR32_PLL1_MUL << PM_PLL_PLLMUL_SHIFT) | (16 << PM_PLL_PLLCOUNT_SHIFT)
+
+ /* Select PLL0/1 oscillator */
+
+#if AVR32_CLOCK_PLL_OSC1
+ regval |= PM_PLL_PLLOSC;
+#endif
+
+ putreg32(regval, AVR32_PM_PLL1);
+
+ /* Set PLL1 options */
+
+ regval = getreg32(AVR32_PM_PLL1);
+ regval &= ~PM_PLL_PLLOPT_MASK
+#if AVR32_PLL1_FREQ < 160000000
+ regval |= PM_PLL_PLLOPT_VCO;
+#endif
+#if AVR32_PLL1_DIV2 != 0
+ regval |= PM_PLL_PLLOPT_XTRADIV;
+#endif
+#if AVR32_PLL1_WBWM != 0
+ regval |= PM_PLL_PLLOPT_WBWDIS;
+#endif
+ putreg32(regval, AVR32_PM_PLL1)
+
+ /* Enable PLL1 */
+
+ regval = getreg32(AVR32_PM_PLL1);
+ regval |= PM_PLL_PLLEN;
+ putreg32(regval, AVR32_PM_PLL1)
+
+ /* Wait for PLL1 locked. */
+
+ while ((getreg32(AVR32_PM_POSCSR) & PM_POSCSR_LOCK1) == 0);
+}
+#endif
+
+/**************************************************************************
+ * Name: up_clksel
+ *
+ * Description:
+ * Configure derived clocks.
+ *
+ **************************************************************************/
+
+static inline void up_clksel(void)
+{
+ uint32_t regval = 0;
+
+#if AVR32_CKSEL_CPUDIV != 0
+ regval |= PM_CKSEL_CPUDIV;
+ regval |= (AVR32_CKSEL_CPUDIV << PM_CKSEL_CPUSEL_SHIFT)
+#endif
+
+#if AVR32_CKSEL_HSBDIV != 0
+ regval |= PM_CKSEL_HSBDIV;
+ regval |= (AVR32_CKSEL_HSBDIV << PM_CKSEL_HSBSEL_SHIFT)
+#endif
+
+#if AVR32_CKSEL_PBADIV != 0
+ regval |= PM_CKSEL_PBADIV;
+ regval |= (AVR32_CKSEL_PBADIV << PM_CKSEL_PBASEL_SHIFT)
+#endif
+
+#if AVR32_CKSEL_PBBDIV != 0
+ regval |= PM_CKSEL_PBBDIV;
+ regval |= (AVR32_CKSEL_PBBDIV << PM_CKSEL_PBBSEL_SHIFT)
+#endif
+
+ putreg32(regval, AVR32_PM_CKSEL);
+
+ /* Wait for CLKRDY */
+
+ while ((getreg32(AVR32_PM_POSCSR) & PM_POSCSR_CKRDY) == 0);
+}
+
+/**************************************************************************
+ * Name: up_fws
+ *
+ * Description:
+ * Setup FLASH wait states.
+ *
+ **************************************************************************/
+
+static void up_fws(uint32_t cpuclock)
+{
+ uint32_t regval;
+
+ regval = getreg32(AVR32_FLASHC_FCR);
+ if (cpuclock > AVR32_FLASHC_FWS0_MAXFREQ)
+ {
+ regval |= FLASHC_FCR_FWS;
+ }
+ else
+ {
+ regval &= ~FLASHC_FCR_FWS;
+ }
+ putreg32(regval, AVR32_FLASHC_FCR);
+}
+
+/**************************************************************************
+ * Name: up_mainclk
+ *
+ * Description:
+ * Select the main clock.
+ *
+ **************************************************************************/
+
+static inline void up_mainclk(uint32_t mcsel)
+{
+ uint32_t regval;
+
+ regval = getreg32(AVR32_PM_MCCTRL);
+ regval &= ~PM_MCCTRL_MCSEL_MASK;
+ regval |= mcsel;
+ putreg32(regval, AVR32_PM_MCCTRL);
+}
+
+/**************************************************************************
+ * Name: up_usbclock
+ *
+ * Description:
+ * Setup the USBB GCLK.
+ *
+ **************************************************************************/
+
+#ifdef CONFIG_USBDEV
+static inline void up_usbclock(void)
+{
+ uint32_t regval = 0;
+
+#if defined(AVR32_CLOCK_USB_PLL0) || defined(AVR32_CLOCK_USB_PLL1)
+ regval |= PM_GCCTRL_PLLSEL;
+#endif
+#if defined(AVR32_CLOCK_USB_OSC1) || defined(AVR32_CLOCK_USB_PLL1)
+ regval |= PM_GCCTRL_OSCSEL;
+#endif
+#if AVR32_CLOCK_USB_DIV > 0
+
+
+ u_avr32_pm_gcctrl.GCCTRL.diven = diven;
+ u_avr32_pm_gcctrl.GCCTRL.div = div;
+#endif
+ putreg32(regval, AVR32_PM_GCCTRL(AVR32_PM_GCLK_USBB))
+
+ /* Enable USB GCLK */
+
+ regval = getreg32(AVR32_PM_GCCTRL(AVR32_PM_GCLK_USBB))
+ regval |= PM_GCCTRL_CEN;
+ putreg32(regval, AVR32_PM_GCCTRL(AVR32_PM_GCLK_USBB))
+}
+#endif
+
+/**************************************************************************
+ * Public Functions
+ **************************************************************************/
+
+/**************************************************************************
+ * Name: up_clkinit
+ *
+ * Description:
+ * Initialiaze clock/PLL settings per the definitions in the board.h
+ * file.
+ *
+ **************************************************************************/
+
+void up_clkinitialize(void)
+{
+ /* Enable the 32KHz oscillator (need by the RTC module) */
+
+ up_enableosc32();
+
+#ifdef NEED_OSC0
+ /* Enable OSC0 using the settings in board.h */
+
+ up_enableosc0();
+
+ /* Set up FLASH wait states */
+
+ up_fws(AVR32_FOSC0);
+
+ /* Then switch the main clock to OSC0 */
+
+ up_mainclk(PM_MCCTRL_MCSEL_OSC0);
+#endif
+
+#ifdef NEED_OSC1
+ /* Enable OSC1 using the settings in board.h */
+
+ up_enableosc1();
+#endif
+
+#ifdef AVR32_CLOCK_PLL0
+ /* Enable PLL0 using the settings in board.h */
+
+ up_enablepll0();
+
+ /* Set up FLASH wait states */
+
+ up_fws(AVR32_CPU_CLOCK);
+
+ /* Then switch the main clock to PLL0 */
+
+ up_mainclk(PM_MCCTRL_MCSEL_PLL0);
+#endif
+
+#ifdef AVR32_CLOCK_PLL1
+ /* Enable PLL1 using the settings in board.h */
+
+ up_enablepll1();
+#endif
+
+ /* Configure derived clocks */
+
+ up_clksel();
+
+ /* Set up the USBB GCLK */
+
+#ifdef CONFIG_USBDEV
+ void up_usbclock();
+#endif
+}
+
+
+
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_config.h b/nuttx/arch/avr/src/at32uc3/at32uc3_config.h
new file mode 100644
index 000000000..004c8b2d1
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_config.h
@@ -0,0 +1,176 @@
+/************************************************************************************
+ * arch/avr/src/at32uc3/at32uc3_config.h
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_AVR_SRC_AT32UC3_AT32UC3_CONFIG_H
+#define __ARCH_AVR_SRC_AT32UC3_AT32UC3_CONFIG_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include "chip.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* USART can be configured as a number of different devices (Only UART is supported
+ * here now, that will be extended). Check for consistency between USART enable
+ * options.
+ */
+
+#if AVR32_NUSART < 1
+# undef CONFIG_AVR32_USART0
+# undef CONFIG_AVR32_USART1
+# undef CONFIG_AVR32_USART2
+#endif
+#if AVR32_NUSART < 2
+# undef CONFIG_AVR32_USART1
+# undef CONFIG_AVR32_USART2
+#endif
+#if AVR32_NUSART < 3
+# undef CONFIG_AVR32_USART2
+#endif
+
+/* Not all USART features are supported on all chips or all USARTS */
+
+#ifdef CONFIG_ARCH_CHIP_AT32UC3B
+# undef CONFIG_AVR32_USART0_RS485
+# undef CONFIG_AVR32_USART0_MAN
+# undef CONFIG_AVR32_USART0_MODEM
+# undef CONFIG_AVR32_USART0_IRDA
+# undef CONFIG_AVR32_USART0_ISO786
+# undef CONFIG_AVR32_USART1_RS485
+# undef CONFIG_AVR32_USART2_RS485
+# undef CONFIG_AVR32_USART2_MAN
+# undef CONFIG_AVR32_USART2_MODEM
+# undef CONFIG_AVR32_USART2_IRDA
+# undef CONFIG_AVR32_USART2_ISO786
+#endif
+
+/* Disable configurations if USART not selected in configuration file */
+
+#ifndef CONFIG_AVR32_USART0
+# undef CONFIG_AVR32_USART0_RS232
+# undef CONFIG_AVR32_USART0_SPI
+# undef CONFIG_AVR32_USART0_RS485
+# undef CONFIG_AVR32_USART0_MAN
+# undef CONFIG_AVR32_USART0_MODEM
+# undef CONFIG_AVR32_USART0_IRDA
+# undef CONFIG_AVR32_USART0_ISO786
+#endif
+
+#ifndef CONFIG_AVR32_USART1
+# undef CONFIG_AVR32_USART1_RS232
+# undef CONFIG_AVR32_USART1_SPI
+# undef CONFIG_AVR32_USART1_RS485
+# undef CONFIG_AVR32_USART1_MAN
+# undef CONFIG_AVR32_USART1_MODEM
+# undef CONFIG_AVR32_USART1_IRDA
+# undef CONFIG_AVR32_USART1_ISO786
+#endif
+
+#ifndef CONFIG_AVR32_USART2
+# undef CONFIG_AVR32_USART2_RS232
+# undef CONFIG_AVR32_USART2_SPI
+# undef CONFIG_AVR32_USART2_RS485
+# undef CONFIG_AVR32_USART2_MAN
+# undef CONFIG_AVR32_USART2_MODEM
+# undef CONFIG_AVR32_USART2_IRDA
+# undef CONFIG_AVR32_USART2_ISO786
+#endif
+
+/* Is any UART configured? */
+
+#if defined(CONFIG_AVR32_USART0_RS232) || \
+ defined(CONFIG_AVR32_USART1_RS232) || \
+ defined(CONFIG_AVR32_USART2_RS232)
+# define HAVE_RS232_DEVICE
+#else
+# undef HAVE_RS232_DEVICE
+#endif
+
+/* Is there a serial console? */
+
+#if defined(CONFIG_USART0_SERIAL_CONSOLE) && defined(CONFIG_AVR32_USART0_RS232)
+# undef CONFIG_USART1_SERIAL_CONSOLE
+# undef CONFIG_USART2_SERIAL_CONSOLE
+# define HAVE_SERIAL_CONSOLE 1
+#elif defined(CONFIG_USART1_SERIAL_CONSOLE) && defined(CONFIG_AVR32_USART1_RS232)
+# undef CONFIG_USART0_SERIAL_CONSOLE
+# undef CONFIG_USART2_SERIAL_CONSOLE
+# define HAVE_SERIAL_CONSOLE 1
+#elif defined(CONFIG_USART2_SERIAL_CONSOLE) && defined(CONFIG_AVR32_USART2_RS232)
+# undef CONFIG_USART0_SERIAL_CONSOLE
+# undef CONFIG_USART1_SERIAL_CONSOLE
+# define HAVE_SERIAL_CONSOLE 1
+#else
+# undef CONFIG_USART0_SERIAL_CONSOLE
+# undef CONFIG_USART1_SERIAL_CONSOLE
+# undef CONFIG_USART2_SERIAL_CONSOLE
+# undef HAVE_SERIAL_CONSOLE
+#endif
+
+/* Determine which (if any) console driver to use */
+
+#if CONFIG_NFILE_DESCRIPTORS == 0 || defined(CONFIG_DEV_LOWCONSOLE) || !defined(HAVE_RS232_DEVICE)
+# undef CONFIG_USE_SERIALDRIVER
+# undef CONFIG_USE_EARLYSERIALINIT
+#elif defined(CONFIG_DEV_CONSOLE) && CONFIG_NFILE_DESCRIPTORS > 0
+# define CONFIG_USE_SERIALDRIVER 1
+# define CONFIG_USE_EARLYSERIALINIT 1
+#endif
+
+/* If GPIO IRQ support is defined, then a set of GPIOs must all be included */
+
+#if CONFIG_AVR32_GPIOIRQSETA == 0 && CONFIG_AVR32_GPIOIRQSETB == 0
+# undef CONFIG_AVR32_GPIOIRQ
+#endif
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_AVR_SRC_AT32UC3_AT32UC3_CONFIG_H */
+
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_eic.h b/nuttx/arch/avr/src/at32uc3/at32uc3_eic.h
new file mode 100644
index 000000000..505d0b84b
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_eic.h
@@ -0,0 +1,133 @@
+/************************************************************************************
+ * arch/avr/src/at32uc3/at32uc3_eic.h
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_AVR_SRC_AT32UC3_AT32UC3_EIC_H
+#define __ARCH_AVR_SRC_AT32UC3_AT32UC3_EIC_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+
+#define AVR32_EIC_IER_OFFSET 0x000 /* Interrupt Enable Register */
+#define AVR32_EIC_IDR_OFFSET 0x004 /* Interrupt Disable Register */
+#define AVR32_EIC_IMR_OFFSET 0x008 /* Interrupt Mask Register */
+#define AVR32_EIC_ISR_OFFSET 0x00c /* Interrupt Status Register */
+#define AVR32_EIC_ICR_OFFSET 0x010 /* Interrupt Clear Register */
+#define AVR32_EIC_MODE_OFFSET 0x014 /* Mode Register */
+#define AVR32_EIC_EDGE_OFFSET 0x018 /* Edge Register */
+#define AVR32_EIC_LEVEL_OFFSET 0x01c /* Level Register */
+#define AVR32_EIC_FILTER_OFFSET 0x020 /* Filter Register */
+#define AVR32_EIC_TEST_OFFSET 0x024 /* Test Register */
+#define AVR32_EIC_ASYNC_OFFSET 0x028 /* Asynchronous Register */
+#define AVR32_EIC_SCAN_OFFSET 0x02c /* Scan Register */
+#define AVR32_EIC_EN_OFFSET 0x030 /* Enable Register */
+#define AVR32_EIC_DIS_OFFSET 0x034 /* Disable Register */
+#define AVR32_EIC_CTRL_OFFSET 0x038 /* Control Register */
+
+/* Register Addresses ***************************************************************/
+
+#define AVR32_EIC_IER (AVR32_EIC_BASE+AVR32_EIC_IER_OFFSET)
+#define AVR32_EIC_IDR (AVR32_EIC_BASE+AVR32_EIC_IDR_OFFSET)
+#define AVR32_EIC_IMR (AVR32_EIC_BASE+AVR32_EIC_IMR_OFFSET)
+#define AVR32_EIC_ISR (AVR32_EIC_BASE+AVR32_EIC_ISR_OFFSET)
+#define AVR32_EIC_ICR (AVR32_EIC_BASE+AVR32_EIC_ICR_OFFSET)
+#define AVR32_EIC_MODE (AVR32_EIC_BASE+AVR32_EIC_MODE_OFFSET)
+#define AVR32_EIC_EDGE (AVR32_EIC_BASE+AVR32_EIC_EDGE_OFFSET)
+#define AVR32_EIC_LEVEL (AVR32_EIC_BASE+AVR32_EIC_LEVEL_OFFSET)
+#define AVR32_EIC_FILTER (AVR32_EIC_BASE+AVR32_EIC_FILTER_OFFSET)
+#define AVR32_EIC_TEST (AVR32_EIC_BASE+AVR32_EIC_TEST_OFFSET)
+#define AVR32_EIC_ASYNC (AVR32_EIC_BASE+AVR32_EIC_ASYNC_OFFSET)
+#define AVR32_EIC_SCAN (AVR32_EIC_BASE+AVR32_EIC_SCAN_OFFSET)
+#define AVR32_EIC_EN (AVR32_EIC_BASE+AVR32_EIC_EN_OFFSET)
+#define AVR32_EIC_DIS (AVR32_EIC_BASE+AVR32_EIC_DIS_OFFSET)
+#define AVR32_EIC_CTRL (AVR32_EIC_BASE+AVR32_EIC_CTRL_OFFSET)
+
+/* Register Bit-field Definitions ***************************************************/
+
+/* Interrupt Enable Register Bit-field Definitions */
+/* Interrupt Disable Register Bit-field Definitions */
+/* Interrupt Mask Register Bit-field Definitions */
+/* Interrupt Status Register Bit-field Definitions */
+/* Interrupt Clear Register Bit-field Definitions */
+/* Mode Register Bit-field Definitions */
+/* Edge Register Bit-field Definitions */
+/* Level Register Bit-field Definitions */
+/* Filter Register Bit-field Definitions */
+/* Test Register Bit-field Definitions */
+/* Asynchronous Register Bit-field Definitions */
+/* Enable Register Bit-field Definitions */
+/* Disable Register Bit-field Definitions */
+/* Control Register Bit-field Definitions */
+
+#define EIC_INT0 (1 << 0) /* Bit 0: External interrupt 0 */
+#define EIC_INT1 (1 << 1) /* Bit 1: External interrupt 1 */
+#define EIC_INT2 (1 << 2) /* Bit 2: External interrupt 2 */
+#define EIC_INT3 (1 << 3) /* Bit 3: External interrupt 3 */
+#define EIC_INT4 (1 << 4) /* Bit 4: External interrupt 4 */
+#define EIC_INT5 (1 << 5) /* Bit 5: External interrupt 5 */
+#define EIC_INT6 (1 << 6) /* Bit 6: External interrupt 6 */
+#define EIC_INT7 (1 << 7) /* Bit 7: External interrupt 7 */
+#define EIC_NMI (1 << 8) /* Bit 8: NMI */
+
+/* Scan Register Bit-field Definitions */
+
+#define EIC_SCAN_PIN_SHIFT (24) /* Bit 24-26: Currently active scan pin */
+#define EIC_SCAN_PIN_MASK (7 << EIC_SCAN_PIN_SHIFT)
+#define EIC_SCAN_PRESC_SHIFT (8) /* Bit 8-12: Prescale select for keypad scan rate */
+#define EIC_SCAN_PRESC_MASK (0x1f << EIC_SCAN_PRESC_SHIFT)
+#define EIC_SCAN_EN (1 << 0) /* Bit 0: Enable keypad scanning */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_AVR_SRC_AT32UC3_AT32UC3_EIC_H */
+
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_flashc.h b/nuttx/arch/avr/src/at32uc3/at32uc3_flashc.h
new file mode 100644
index 000000000..45df326ba
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_flashc.h
@@ -0,0 +1,229 @@
+/************************************************************************************
+ * arch/avr/src/at32uc3/at32uc3_flashc.h
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_AVR_SRC_AT32UC3_AT32UC3_FLASHC_H
+#define __ARCH_AVR_SRC_AT32UC3_AT32UC3_FLASHC_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+
+#define AVR32_FLASHC_FCR_OFFSET 0x00 /* Flash Control Register */
+#define AVR32_FLASHC_FCMD_OFFSET 0x04 /* Flash Command Register */
+#define AVR32_FLASHC_FSR_OFFSET 0x08 /* Flash Status Register */
+#define AVR32_FLASHC_FGPFRHI_OFFSET 0x0c /* Flash General Purpose Fuse Register Hi */
+#define AVR32_FLASHC_FGPFRLO_OFFSET 0x10 /* Flash General Purpose Fuse Register Lo */
+
+/* Register Addresses ***************************************************************/
+
+#define AVR32_FLASHC_FCR (AVR32_HFLASHC_BASE+AVR32_FLASHC_FCR_OFFSET)
+#define AVR32_FLASHC_FCMD (AVR32_HFLASHC_BASE+AVR32_FLASHC_FCMD_OFFSET)
+#define AVR32_FLASHC_FSR (AVR32_HFLASHC_BASE+AVR32_FLASHC_FSR_OFFSET)
+#define AVR32_FLASHC_FGPFRHI (AVR32_HFLASHC_BASE+AVR32_FLASHC_FGPFRHI_OFFSET)
+#define AVR32_FLASHC_FGPFRLO (AVR32_HFLASHC_BASE+AVR32_FLASHC_FGPFRLO_OFFSET)
+
+/* Register Bit-field Definitions ***************************************************/
+
+/* Flash Control Register */
+
+#define FLASHC_FCR_FRDY (1 << 0) /* Bit 0: Flash Ready Interrupt Enable */
+#define FLASHC_FCR_LOCKE (1 << 2) /* Bit 2: Lock Error Interrupt Enable */
+#define FLASHC_FCR_PROGE (1 << 3) /* Bit 3: Programming Error Interrupt Enable */
+#define FLASHC_FCR_FWS (1 << 6) /* Bit 6: Flash Wait State */
+
+/* Flash Command Register */
+
+#define FLASHC_FCMD_CMD_SHIFT (0) /* Bits 0-5: Command */
+#define FLASHC_FCMD_CMD_MASK (0x3f << FLASHC_FCMD_CMD_SHIFT)
+#define FLASHC_FCMD_PAGEN_SHIFT (8) /* Bits 8-23: Page number */
+#define FLASHC_FCMD_PAGEN_MASK (0xffff << FLASHC_FCMD_PAGEN_SHIFT)
+#define FLASHC_FCMD_KEY_SHIFT (14) /* Bits 24-31: Write protection key */
+#define FLASHC_FCMD_KEY_MASK (0xff << FLASHC_FCMD_KEY_SHIFT)
+
+/* Flash Status Register */
+
+#define FLASHC_FSR_FRDY (1 << 0) /* Bit 0: Flash Ready Status */
+#define FLASHC_FSR_LOCKE (1 << 2) /* Bit 2: Lock Error Status */
+#define FLASHC_FSR_PROGE (1 << 3) /* Bit 3: Programming Error Status */
+#define FLASHC_FSR_SECURITY (1 << 4) /* Bit 4: Security Bit Status */
+#define FLASHC_FSR_QPRR (1 << 5) /* Bit 5: Quick Page Read Result */
+#define FLASHC_FSR_FSZ_SHIFT (13) /* Bits 13-15: Flash Size */
+#define FLASHC_FSR_FSZ_MASK (7 << FLASHC_FSR_FSZ_SHIFT)
+# define FLASHC_FSR_FSZ_23KB (0 << FLASHC_FSR_FSZ_SHIFT) /* 32 Kbytes */
+# define FLASHC_FSR_FSZ_64KB (1 << FLASHC_FSR_FSZ_SHIFT) /* 64 Kbytes */
+# define FLASHC_FSR_FSZ_128KB (2 << FLASHC_FSR_FSZ_SHIFT) /* 128 Kbytes */
+# define FLASHC_FSR_FSZ_256KB (3 << FLASHC_FSR_FSZ_SHIFT) /* 256 Kbytes */
+# define FLASHC_FSR_FSZ_384KB (4 << FLASHC_FSR_FSZ_SHIFT) /* 384 Kbytes */
+# define FLASHC_FSR_FSZ_512KGB (5 << FLASHC_FSR_FSZ_SHIFT) /* 512 Kbytes */
+# define FLASHC_FSR_FSZ_768KB (6 << FLASHC_FSR_FSZ_SHIFT) /* 768 Kbytes */
+# define FLASHC_FSR_FSZ_1MB (7 << FLASHC_FSR_FSZ_SHIFT) /* 1024 Kbytes */
+#define FLASHC_FSR_LOCK(n) (1 << ((n)+16)
+#define FLASHC_FSR_LOCK0 (1 << 16) /* Bit 16: Lock Region 0 Lock Status */
+#define FLASHC_FSR_LOCK1 (1 << 17) /* Bit 17: Lock Region 1 Lock Status */
+#define FLASHC_FSR_LOCK2 (1 << 18) /* Bit 18: Lock Region 2 Lock Status */
+#define FLASHC_FSR_LOCK3 (1 << 19) /* Bit 19: Lock Region 3 Lock Status */
+#define FLASHC_FSR_LOCK4 (1 << 20) /* Bit 20: Lock Region 4 Lock Status */
+#define FLASHC_FSR_LOCK5 (1 << 21) /* Bit 21: Lock Region 5 Lock Status */
+#define FLASHC_FSR_LOCK6 (1 << 22) /* Bit 22: Lock Region 6 Lock Status */
+#define FLASHC_FSR_LOCK7 (1 << 23) /* Bit 23: Lock Region 7 Lock Status */
+#define FLASHC_FSR_LOCK8 (1 << 24) /* Bit 24: Lock Region 8 Lock Status */
+#define FLASHC_FSR_LOCK9 (1 << 25) /* Bit 25: Lock Region 9 Lock Status */
+#define FLASHC_FSR_LOCK10 (1 << 26) /* Bit 26: Lock Region 10 Lock Status */
+#define FLASHC_FSR_LOCK11 (1 << 27) /* Bit 27: Lock Region 11 Lock Status */
+#define FLASHC_FSR_LOCK12 (1 << 28) /* Bit 28: Lock Region 12 Lock Status */
+#define FLASHC_FSR_LOCK13 (1 << 29) /* Bit 29: Lock Region 13 Lock Status */
+#define FLASHC_FSR_LOCK14 (1 << 30) /* Bit 30: Lock Region 14 Lock Status */
+#define FLASHC_FSR_LOCK15 (1 << 31) /* Bit 31: Lock Region 15 Lock Status */
+
+/* Flash General Purpose Fuse Register Hi */
+
+#define FLASHC_FGPFRHI(n) (1 << ((n)-32))
+#define FLASHC_FGPFRHI32 (1 << 0) /* Bit 0: General Purpose Fuse 32 */
+#define FLASHC_FGPFRHI33 (1 << 1) /* Bit 1: General Purpose Fuse 33 */
+#define FLASHC_FGPFRHI34 (1 << 2) /* Bit 2: General Purpose Fuse 34 */
+#define FLASHC_FGPFRHI35 (1 << 3) /* Bit 3: General Purpose Fuse 35 */
+#define FLASHC_FGPFRHI36 (1 << 4) /* Bit 4: General Purpose Fuse 36 */
+#define FLASHC_FGPFRHI37 (1 << 5) /* Bit 5: General Purpose Fuse 37 */
+#define FLASHC_FGPFRHI38 (1 << 6) /* Bit 6: General Purpose Fuse 38 */
+#define FLASHC_FGPFRHI39 (1 << 7) /* Bit 7: General Purpose Fuse 39 */
+#define FLASHC_FGPFRHI40 (1 << 8) /* Bit 8: General Purpose Fuse 40 */
+#define FLASHC_FGPFRHI41 (1 << 9) /* Bit 9: General Purpose Fuse 41 */
+#define FLASHC_FGPFRHI42 (1 << 10) /* Bit 10: General Purpose Fuse 42 */
+#define FLASHC_FGPFRHI43 (1 << 11) /* Bit 11: General Purpose Fuse 43 */
+#define FLASHC_FGPFRHI44 (1 << 12) /* Bit 12: General Purpose Fuse 44 */
+#define FLASHC_FGPFRHI45 (1 << 13) /* Bit 13: General Purpose Fuse 45 */
+#define FLASHC_FGPFRHI46 (1 << 14) /* Bit 14: General Purpose Fuse 46 */
+#define FLASHC_FGPFRHI47 (1 << 15) /* Bit 15: General Purpose Fuse 47 */
+#define FLASHC_FGPFRHI48 (1 << 16) /* Bit 16: General Purpose Fuse 48 */
+#define FLASHC_FGPFRHI49 (1 << 17) /* Bit 17: General Purpose Fuse 49 */
+#define FLASHC_FGPFRHI50 (1 << 18) /* Bit 18: General Purpose Fuse 50 */
+#define FLASHC_FGPFRHI51 (1 << 19) /* Bit 19: General Purpose Fuse 51 */
+#define FLASHC_FGPFRHI52 (1 << 20) /* Bit 20: General Purpose Fuse 52 */
+#define FLASHC_FGPFRHI53 (1 << 21) /* Bit 21: General Purpose Fuse 53 */
+#define FLASHC_FGPFRHI54 (1 << 22) /* Bit 22: General Purpose Fuse 54 */
+#define FLASHC_FGPFRHI55 (1 << 23) /* Bit 23: General Purpose Fuse 55 */
+#define FLASHC_FGPFRHI56 (1 << 24) /* Bit 24: General Purpose Fuse 56 */
+#define FLASHC_FGPFRHI57 (1 << 25) /* Bit 25: General Purpose Fuse 57 */
+#define FLASHC_FGPFRHI58 (1 << 26) /* Bit 26: General Purpose Fuse 58 */
+#define FLASHC_FGPFRHI59 (1 << 27) /* Bit 27: General Purpose Fuse 59 */
+#define FLASHC_FGPFRHI60 (1 << 28) /* Bit 28: General Purpose Fuse 60 */
+#define FLASHC_FGPFRHI61 (1 << 29) /* Bit 29: General Purpose Fuse 61 */
+#define FLASHC_FGPFRHI62 (1 << 30) /* Bit 30: General Purpose Fuse 62 */
+#define FLASHC_FGPFRHI63 (1 << 31) /* Bit 31: General Purpose Fuse 63 */
+
+/* Flash General Purpose Fuse Register Lo */
+
+#define FLASHC_FGPFRLO(n) (1 << (n))
+#define FLASHC_FGPFRLO00 (1 << 0) /* Bit 0: General Purpose Fuse 00 */
+#define FLASHC_FGPFRLO01 (1 << 1) /* Bit 1: General Purpose Fuse 01 */
+#define FLASHC_FGPFRLO02 (1 << 2) /* Bit 2: General Purpose Fuse 02 */
+#define FLASHC_FGPFRLO03 (1 << 3) /* Bit 3: General Purpose Fuse 03 */
+#define FLASHC_FGPFRLO04 (1 << 4) /* Bit 4: General Purpose Fuse 04 */
+#define FLASHC_FGPFRLO05 (1 << 5) /* Bit 5: General Purpose Fuse 05 */
+#define FLASHC_FGPFRLO06 (1 << 6) /* Bit 6: General Purpose Fuse 06 */
+#define FLASHC_FGPFRLO07 (1 << 7) /* Bit 7: General Purpose Fuse 07 */
+#define FLASHC_FGPFRLO08 (1 << 8) /* Bit 8: General Purpose Fuse 08 */
+#define FLASHC_FGPFRLO09 (1 << 9) /* Bit 9: General Purpose Fuse 09 */
+#define FLASHC_FGPFRLO10 (1 << 10) /* Bit 10: General Purpose Fuse 10 */
+#define FLASHC_FGPFRLO11 (1 << 11) /* Bit 11: General Purpose Fuse 11 */
+#define FLASHC_FGPFRLO12 (1 << 12) /* Bit 12: General Purpose Fuse 12 */
+#define FLASHC_FGPFRLO13 (1 << 13) /* Bit 13: General Purpose Fuse 13 */
+#define FLASHC_FGPFRLO14 (1 << 14) /* Bit 14: General Purpose Fuse 14 */
+#define FLASHC_FGPFRLO15 (1 << 15) /* Bit 15: General Purpose Fuse 15 */
+#define FLASHC_FGPFRLO16 (1 << 16) /* Bit 16: General Purpose Fuse 16 */
+#define FLASHC_FGPFRLO17 (1 << 17) /* Bit 17: General Purpose Fuse 17 */
+#define FLASHC_FGPFRLO18 (1 << 18) /* Bit 18: General Purpose Fuse 18 */
+#define FLASHC_FGPFRLO19 (1 << 19) /* Bit 19: General Purpose Fuse 19 */
+#define FLASHC_FGPFRLO20 (1 << 20) /* Bit 20: General Purpose Fuse 20 */
+#define FLASHC_FGPFRLO21 (1 << 21) /* Bit 21: General Purpose Fuse 21 */
+#define FLASHC_FGPFRLO22 (1 << 22) /* Bit 22: General Purpose Fuse 22 */
+#define FLASHC_FGPFRLO23 (1 << 23) /* Bit 23: General Purpose Fuse 23 */
+#define FLASHC_FGPFRLO24 (1 << 24) /* Bit 24: General Purpose Fuse 24 */
+#define FLASHC_FGPFRLO25 (1 << 25) /* Bit 25: General Purpose Fuse 25 */
+#define FLASHC_FGPFRLO26 (1 << 26) /* Bit 26: General Purpose Fuse 26 */
+#define FLASHC_FGPFRLO27 (1 << 27) /* Bit 27: General Purpose Fuse 27 */
+#define FLASHC_FGPFRLO28 (1 << 28) /* Bit 28: General Purpose Fuse 28 */
+#define FLASHC_FGPFRLO29 (1 << 29) /* Bit 29: General Purpose Fuse 29 */
+#define FLASHC_FGPFRLO30 (1 << 30) /* Bit 30: General Purpose Fuse 30 */
+#define FLASHC_FGPFRLO31 (1 << 31) /* Bit 31: General Purpose Fuse 31 */
+
+/* Flash Command Set ****************************************************************/
+
+#define FLASH_CMD_NOP 0 /* No operation */
+#define FLASH_CMD_WP 1 /* Write Page */
+#define FLASH_CMD_EP 2 /* Erase Page */
+#define FLASH_CMD_CPB 3 /* Clear Page Buffer */
+#define FLASH_CMD_LP 4 /* Lock region containing given page */
+#define FLASH_CMD_UP 5 /* Unlock region containing given page */
+#define FLASH_CMD_EA 6 /* Erase All */
+#define FLASH_CMD_WGPB 7 /* Write General-Purpose Fuse Bit */
+#define FLASH_CMD_EGPB 8 /* Erase General-Purpose Fuse Bit */
+#define FLASH_CMD_SSB 9 /* Set Security Bit */
+#define FLASH_CMD_PGPFB 10 /* Program GP Fuse Byte */
+#define FLASH_CMD_EAGP 11 /* Erase All GPFuses */
+#define FLASH_CMD_QPR 12 /* Quick Page Read */
+#define FLASH_CMD_WUP 13 /* Write User Page */
+#define FLASH_CMD_EUP 14 /* Erase User Page */
+#define FLASH_CMD_QPRUP 15 /* Quick Page Read User Page */
+
+/* Other constants ******************************************************************/
+
+/* Maximum CPU frequency for 0 and 1 FLASH wait states */
+
+#define AVR32_FLASHC_FWS0_MAXFREQ 33000000
+#define AVR32_FLASHC_FWS1_MAXFREQ 66000000
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_AVR_SRC_AT32UC3_AT32UC3_FLASHC_H */
+
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_gpio.c b/nuttx/arch/avr/src/at32uc3/at32uc3_gpio.c
new file mode 100644
index 000000000..4ca7b7b2e
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_gpio.c
@@ -0,0 +1,296 @@
+/**************************************************************************
+ * arch/avr/src/at32uc3/at32uc3_gpio.c
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ **************************************************************************/
+
+/**************************************************************************
+ * Included Files
+ **************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <assert.h>
+
+#include "at32uc3_config.h"
+#include "up_internal.h"
+#include "at32uc3_internal.h"
+
+#include "up_arch.h"
+#include "chip.h"
+#include "at32uc3_gpio.h"
+
+/**************************************************************************
+ * Private Definitions
+ **************************************************************************/
+
+/* How many GPIO ports are supported? There are 32-pins per port and we
+ * know he number of GPIO pins supported by the architecture:
+ */
+
+#define AVR32_NGPIO_PORTS ((AVR32_NGPIO+31) >> 5)
+
+/**************************************************************************
+ * Private Types
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Function Prototypes
+ **************************************************************************/
+
+/**************************************************************************
+ * Global Variables
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Variables
+ **************************************************************************/
+
+static uint32_t g_portmap[AVR32_NGPIO_PORTS] =
+{
+#if AVR32_NGPIO > 0
+ AVR32_GPIO0_BASE
+#endif
+#if AVR32_NGPIO > 32
+ , AVR32_GPIO1_BASE,
+#endif
+#if AVR32_NGPIO > 64
+ , AVR32_GPIO2_BASE,
+#endif
+#if AVR32_NGPIO > 96
+ , AVR32_GPIO3_BASE,
+#endif
+#if AVR32_NGPIO > 128
+ , AVR32_GPIO4_BASE,
+#endif
+};
+
+/**************************************************************************
+ * Private Functions
+ **************************************************************************/
+
+/**************************************************************************
+ * Public Functions
+ **************************************************************************/
+
+/************************************************************************************
+ * Name: at32uc3_configgpio
+ *
+ * Description:
+ * Configure a GPIO pin based on bit-encoded description of the pin.
+ *
+ ************************************************************************************/
+
+int at32uc3_configgpio(uint16_t cfgset)
+{
+ unsigned int port;
+ unsigned int pin;
+ uint32_t pinmask;
+ uint32_t base;
+
+ /* Extract then port number and the pin number from the configuration */
+
+ port = ((unsigned int)cfgset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
+ pin = ((unsigned int)cfgset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
+ DEBUGASSERT(port < AVR32_NGPIO_PORTS);
+
+ /* Get pin mask and the GPIO base address */
+
+ pinmask = (1 << pin);
+ base = g_portmap[port];
+
+ /* First, just to be safe, disable the output driver, give GPIO control of
+ * the pin, rese the peripheral mux, set the output low, remove the pull-up,
+ * disable GPIO interrupts, reset the interrupt mode, and disable glitch
+ * filtering, while we reconfigure the pin.
+ */
+
+ putreg32(pinmask, base + AVR32_GPIO_ODERC_OFFSET);
+ putreg32(pinmask, base + AVR32_GPIO_GPERS_OFFSET);
+ putreg32(pinmask, base + AVR32_GPIO_PMR0C_OFFSET);
+ putreg32(pinmask, base + AVR32_GPIO_PMR1C_OFFSET);
+ putreg32(pinmask, base + AVR32_GPIO_OVRC_OFFSET);
+ putreg32(pinmask, base + AVR32_GPIO_PUERC_OFFSET);
+ putreg32(pinmask, base + AVR32_GPIO_IERC_OFFSET);
+ putreg32(pinmask, base + AVR32_GPIO_IMR0C_OFFSET);
+ putreg32(pinmask, base + AVR32_GPIO_IMR0C_OFFSET);
+ putreg32(pinmask, base + AVR32_GPIO_GFERC_OFFSET);
+
+ /* Is this a GPIO? Or a peripheral */
+
+ if ((cfgset & GPIO_ENABLE) != 0)
+ {
+ /* Its a GPIO. Input or output? */
+
+ if ((cfgset & GPIO_OUTPUT) != 0)
+ {
+ /* Its a GPIO output. Set up the initial output value and enable
+ * the output driver.
+ */
+
+ if ((cfgset & GPIO_VALUE) != 0)
+ {
+ putreg32(pinmask, base + AVR32_GPIO_OVRS_OFFSET);
+ }
+ putreg32(pinmask, base + AVR32_GPIO_ODERS_OFFSET);
+ }
+ else
+ {
+ /* Its a GPIO input. There is nothing more to do here. */
+ }
+ }
+ else
+ {
+ /* Its a peripheral. Set the peripheral mux */
+
+ if ((cfgset & GPIO_PMR0) != 0)
+ {
+ putreg32(pinmask, base + AVR32_GPIO_PMR0S_OFFSET);
+ }
+
+ if ((cfgset & GPIO_PMR1) != 0)
+ {
+ putreg32(pinmask, base + AVR32_GPIO_PMR1S_OFFSET);
+ }
+
+ /* And enable peripheral control of the pin */
+
+ putreg32(pinmask, base + AVR32_GPIO_GPERC_OFFSET);
+ }
+
+ /* Then the "ornaments" tha do not depend on gpio/peripheral mode:
+ * Pull-ups and glitch filering.
+ */
+
+ if ((cfgset & GPIO_PULLUP) != 0)
+ {
+ putreg32(pinmask, base + AVR32_GPIO_PUERS_OFFSET);
+ }
+
+ if ((cfgset & GPIO_PULLUP) != 0)
+ {
+ putreg32(pinmask, base + AVR32_GPIO_GFERS_OFFSET);
+ }
+
+ /* Check for GPIO interrupt */
+
+ if ((cfgset & GPIO_INTR) != 0)
+ {
+ /* Set up the interrupt mode */
+
+ if ((cfgset & GPIO_IMR0) != 0)
+ {
+ putreg32(pinmask, base + AVR32_GPIO_IMR0S_OFFSET);
+ }
+
+ if ((cfgset & GPIO_IMR1) != 0)
+ {
+ putreg32(pinmask, base + AVR32_GPIO_IMR1S_OFFSET);
+ }
+
+ /* Then enable the GPIO interrupt */
+
+ putreg32(pinmask, base + AVR32_GPIO_IERS_OFFSET);
+ }
+
+ return OK;
+}
+
+/************************************************************************************
+ * Name: at32uc3_gpiowrite
+ *
+ * Description:
+ * Write one or zero to the selected GPIO pin
+ *
+ ************************************************************************************/
+
+void at32uc3_gpiowrite(uint16_t pinset, bool value)
+{
+ unsigned int port;
+ unsigned int pin;
+ uint32_t pinmask;
+ uint32_t base;
+
+ /* Extract then port number and the pin number from the configuration */
+
+ port = ((unsigned int)pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
+ pin = ((unsigned int)pinset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
+ DEBUGASSERT(port < AVR32_NGPIO_PORTS);
+
+ /* Get pin mask and the GPIO base address */
+
+ pinmask = (1 << pin);
+ base = g_portmap[port];
+
+ /* Now, set or clear the pin ouput value */
+
+ if (value)
+ {
+ putreg32(pinmask, base + AVR32_GPIO_OVRS_OFFSET);
+ }
+ else
+ {
+ putreg32(pinmask, base + AVR32_GPIO_OVRC_OFFSET);
+ }
+}
+
+/************************************************************************************
+ * Name: at32uc3_gpioread
+ *
+ * Description:
+ * Read one or zero from the selected GPIO pin
+ *
+ ************************************************************************************/
+
+bool at32uc3_gpioread(uint16_t pinset)
+{
+ unsigned int port;
+ unsigned int pin;
+ uint32_t pinmask;
+ uint32_t base;
+
+ /* Extract then port number and the pin number from the configuration */
+
+ port = ((unsigned int)pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
+ pin = ((unsigned int)pinset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
+ DEBUGASSERT(port < AVR32_NGPIO_PORTS);
+
+ /* Get pin mask and the GPIO base address */
+
+ pinmask = (1 << pin);
+ base = g_portmap[port];
+
+ /* Now, return the current pin value */
+
+ return (getreg32(base + AVR32_GPIO_PVR_OFFSET) & pinmask) != 0;
+}
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_gpio.h b/nuttx/arch/avr/src/at32uc3/at32uc3_gpio.h
new file mode 100644
index 000000000..b5f377efb
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_gpio.h
@@ -0,0 +1,465 @@
+/************************************************************************************
+ * arch/avr/src/at32uc3/at32uc3_gpio.h
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_AVR_SRC_AT32UC3_AT32UC3_GPIO_H
+#define __ARCH_AVR_SRC_AT32UC3_AT32UC3_GPIO_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+/* Port Identifiers *****************************************************************/
+
+#define AVR32_GPIO0 0 /* General Purpose Input/Output Port 0 */
+#define AVR32_GPIO1 1 /* General Purpose Input/Output Port 1 */
+#define AVR32_GPIO2 2 /* General Purpose Input/Output Port 2 */
+#define AVR32_GPIO3 3 /* General Purpose Input/Output Port 3 */
+#define AVR32_GPIO4 4 /* General Purpose Input/Output Port 4 */
+
+/* Port Offsets *********************************************************************/
+
+#define AVR32_GPIOn_OFFSET(n) ((n) << 8)
+#define AVR32_GPIO0_OFFSET 0x0000 /* General Purpose Input/Output Port 0 */
+#define AVR32_GPIO1_OFFSET 0x0100 /* General Purpose Input/Output Port 1 */
+#define AVR32_GPIO2_OFFSET 0x0200 /* General Purpose Input/Output Port 2 */
+#define AVR32_GPIO3_OFFSET 0x0300 /* General Purpose Input/Output Port 3 */
+#define AVR32_GPIO4_OFFSET 0x0400 /* General Purpose Input/Output Port 4 */
+
+/* Register offsets *****************************************************************/
+
+#define AVR32_GPIO_GPER_OFFSET 0x00 /* GPIO Enable Register */
+#define AVR32_GPIO_GPERS_OFFSET 0x04 /* GPIO Enable Register Set */
+#define AVR32_GPIO_GPERC_OFFSET 0x08 /* GPIO Enable Register Clear */
+#define AVR32_GPIO_GPERT_OFFSET 0x0c /* GPIO Enable Register Toggle */
+#define AVR32_GPIO_PMR0_OFFSET 0x10 /* Peripheral Mux Register 0 */
+#define AVR32_GPIO_PMR0S_OFFSET 0x14 /* Peripheral Mux Register 0 Set */
+#define AVR32_GPIO_PMR0C_OFFSET 0x18 /* Peripheral Mux Register 0 Clear */
+#define AVR32_GPIO_PMR0T_OFFSET 0x1c /* Peripheral Mux Register 0 Toggle */
+#define AVR32_GPIO_PMR1_OFFSET 0x20 /* Peripheral Mux Register 1 */
+#define AVR32_GPIO_PMR1S_OFFSET 0x24 /* Peripheral Mux Register 1 Set */
+#define AVR32_GPIO_PMR1C_OFFSET 0x28 /* Peripheral Mux Register 1 Clear */
+#define AVR32_GPIO_PMR1T_OFFSET 0x2c /* Peripheral Mux Register 1 Toggle */
+#define AVR32_GPIO_ODER_OFFSET 0x40 /* Output Driver Enable Register */
+#define AVR32_GPIO_ODERS_OFFSET 0x44 /* Output Driver Enable Register Set */
+#define AVR32_GPIO_ODERC_OFFSET 0x48 /* Output Driver Enable Register Clear */
+#define AVR32_GPIO_ODERT_OFFSET 0x4c /* Output Driver Enable Register Toggle */
+#define AVR32_GPIO_OVR_OFFSET 0x50 /* Output Value Register */
+#define AVR32_GPIO_OVRS_OFFSET 0x54 /* Output Value Register Set */
+#define AVR32_GPIO_OVRC_OFFSET 0x58 /* Output Value Register Clear */
+#define AVR32_GPIO_OVRT_OFFSET 0x5c /* Output Value Register Toggle */
+#define AVR32_GPIO_PVR_OFFSET 0x60 /* Pin Value Register Read */
+#define AVR32_GPIO_PUER_OFFSET 0x70 /* Pull-up Enable Register */
+#define AVR32_GPIO_PUERS_OFFSET 0x74 /* Pull-up Enable Register Set */
+#define AVR32_GPIO_PUERC_OFFSET 0x78 /* Pull-up Enable Register Clear */
+#define AVR32_GPIO_PUERT_OFFSET 0x7c /* Pull-up Enable Register Toggle */
+#define AVR32_GPIO_IER_OFFSET 0x90 /* Interrupt Enable Register */
+#define AVR32_GPIO_IERS_OFFSET 0x94 /* Interrupt Enable Register Set */
+#define AVR32_GPIO_IERC_OFFSET 0x98 /* Interrupt Enable Register Clear */
+#define AVR32_GPIO_IERT_OFFSET 0x9c /* Interrupt Enable Register Toggle */
+#define AVR32_GPIO_IMR0_OFFSET 0xa0 /* Interrupt Mode Register 0 */
+#define AVR32_GPIO_IMR0S_OFFSET 0xa4 /* Interrupt Mode Register 0 Set */
+#define AVR32_GPIO_IMR0C_OFFSET 0xa8 /* Interrupt Mode Register 0 Clear */
+#define AVR32_GPIO_IMR0T_OFFSET 0xac /* Interrupt Mode Register 0 Toggle */
+#define AVR32_GPIO_IMR1_OFFSET 0xb0 /* Interrupt Mode Register 1 */
+#define AVR32_GPIO_IMR1S_OFFSET 0xb4 /* Interrupt Mode Register 1 Set */
+#define AVR32_GPIO_IMR1C_OFFSET 0xb8 /* Interrupt Mode Register 1 Clear */
+#define AVR32_GPIO_IMR1T_OFFSET 0xbc /* Interrupt Mode Register 1 Toggle */
+#define AVR32_GPIO_GFER_OFFSET 0xc0 /* Glitch Filter Enable Register */
+#define AVR32_GPIO_GFERS_OFFSET 0xc4 /* Glitch Filter Enable Register Set */
+#define AVR32_GPIO_GFERC_OFFSET 0xc8 /* Glitch Filter Enable Register Clear */
+#define AVR32_GPIO_GFERT_OFFSET 0xcc /* Glitch Filter Enable Register Toggle */
+#define AVR32_GPIO_IFR_OFFSET 0xd0 /* Interrupt Flag Register Read */
+#define AVR32_GPIO_IFRC_OFFSET 0xd8 /* Interrupt Flag Register Clear */
+
+/* Port Base Addresses **************************************************************/
+
+#define AVR32_GPIOn_BASE(n) (AVR32_GPIO_BASE+AVR32_GPIO_OFFSET(n))
+#define AVR32_GPIO0_BASE (AVR32_GPIO_BASE+AVR32_GPIO0_OFFSET)
+#define AVR32_GPIO1_BASE (AVR32_GPIO_BASE+AVR32_GPIO1_OFFSET)
+#define AVR32_GPIO2_BASE (AVR32_GPIO_BASE+AVR32_GPIO2_OFFSET)
+#define AVR32_GPIO3_BASE (AVR32_GPIO_BASE+AVR32_GPIO3_OFFSET)
+#define AVR32_GPIO4_BASE (AVR32_GPIO_BASE+AVR32_GPIO4_OFFSET)
+
+/* Local bus mapped GPIO ports */
+
+#define AVR32_GPIOn_LBUS_BASE(n) (AVR32_GPIO_LBUS_BASE+AVR32_GPIO_OFFSET(n))
+#define AVR32_GPIO0_LBUS_BASE (AVR32_GPIO_LBUS_BASE+AVR32_GPIO0_OFFSET)
+#define AVR32_GPIO1_LBUS_BASE (AVR32_GPIO_LBUS_BASE+AVR32_GPIO1_OFFSET)
+
+/* Register Addresses ***************************************************************/
+
+#define AVR32_GPIO_GPER(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_GPER_OFFSET)
+#define AVR32_GPIO_GPERS(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_GPERS_OFFSET)
+#define AVR32_GPIO_GPERC(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_GPERC_OFFSET)
+#define AVR32_GPIO_GPERT(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_GPERT_OFFSET)
+#define AVR32_GPIO_PMR0(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_PMR0_OFFSET)
+#define AVR32_GPIO_PMR0S(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_PMR0S_OFFSET)
+#define AVR32_GPIO_PMR0C(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_PMR0C_OFFSET)
+#define AVR32_GPIO_PMR0T(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_PMR0T_OFFSET)
+#define AVR32_GPIO_PMR1(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_PMR1_OFFSET)
+#define AVR32_GPIO_PMR1S(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_PMR1S_OFFSET)
+#define AVR32_GPIO_PMR1C(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_PMR1C_OFFSET)
+#define AVR32_GPIO_PMR1T(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_PMR1T_OFFSET)
+#define AVR32_GPIO_ODER(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_ODER_OFFSET)
+#define AVR32_GPIO_ODERS(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_ODERS_OFFSET)
+#define AVR32_GPIO_ODERC(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_ODERC_OFFSET)
+#define AVR32_GPIO_ODERT(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_ODERT_OFFSET)
+#define AVR32_GPIO_OVR(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_OVR_OFFSET)
+#define AVR32_GPIO_OVRS(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_OVRS_OFFSET)
+#define AVR32_GPIO_OVRC(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_OVRC_OFFSET)
+#define AVR32_GPIO_OVRT(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_OVRT_OFFSET)
+#define AVR32_GPIO_PVR(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_PVR_OFFSET)
+#define AVR32_GPIO_PUER(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_PUER_OFFSET)
+#define AVR32_GPIO_PUERS(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_PUERS_OFFSET)
+#define AVR32_GPIO_PUERC(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_PUERC_OFFSET)
+#define AVR32_GPIO_PUERT(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_PUERT_OFFSET)
+#define AVR32_GPIO_IER(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_IER_OFFSET)
+#define AVR32_GPIO_IERS(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_IERS_OFFSET)
+#define AVR32_GPIO_IERC(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_IERC_OFFSET)
+#define AVR32_GPIO_IERT(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_IERT_OFFSET)
+#define AVR32_GPIO_IMR0(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_IMR0_OFFSET)
+#define AVR32_GPIO_IMR0S(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_IMR0S_OFFSET)
+#define AVR32_GPIO_IMR0C(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_IMR0C_OFFSET)
+#define AVR32_GPIO_IMR0T(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_IMR0T_OFFSET)
+#define AVR32_GPIO_IMR1(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_IMR1_OFFSET)
+#define AVR32_GPIO_IMR1S(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_IMR1S_OFFSET)
+#define AVR32_GPIO_IMR1C(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_IMR1C_OFFSET)
+#define AVR32_GPIO_IMR1T(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_IMR1T_OFFSET)
+#define AVR32_GPIO_GFER(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_GFER_OFFSET)
+#define AVR32_GPIO_GFERS(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_GFERS_OFFSET)
+#define AVR32_GPIO_GFERC(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_GFERC_OFFSET)
+#define AVR32_GPIO_GFERT(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_GFERT_OFFSET)
+#define AVR32_GPIO_IFR(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_IFR_OFFSET)
+#define AVR32_GPIO_IFRC(n) (AVR32_GPIOn_BASE(n)+AVR32_GPIO_IFRC_OFFSET)
+
+#define AVR32_GPIO0_GPER (AVR32_GPIO0_BASE+AVR32_GPIO_GPER_OFFSET)
+#define AVR32_GPIO0_GPERS (AVR32_GPIO0_BASE+AVR32_GPIO_GPERS_OFFSET)
+#define AVR32_GPIO0_GPERC (AVR32_GPIO0_BASE+AVR32_GPIO_GPERC_OFFSET)
+#define AVR32_GPIO0_GPERT (AVR32_GPIO0_BASE+AVR32_GPIO_GPERT_OFFSET)
+#define AVR32_GPIO0_PMR0 (AVR32_GPIO0_BASE+AVR32_GPIO_PMR0_OFFSET)
+#define AVR32_GPIO0_PMR0S (AVR32_GPIO0_BASE+AVR32_GPIO_PMR0S_OFFSET)
+#define AVR32_GPIO0_PMR0C (AVR32_GPIO0_BASE+AVR32_GPIO_PMR0C_OFFSET)
+#define AVR32_GPIO0_PMR0T (AVR32_GPIO0_BASE+AVR32_GPIO_PMR0T_OFFSET)
+#define AVR32_GPIO0_PMR1 (AVR32_GPIO0_BASE+AVR32_GPIO_PMR1_OFFSET)
+#define AVR32_GPIO0_PMR1S (AVR32_GPIO0_BASE+AVR32_GPIO_PMR1S_OFFSET)
+#define AVR32_GPIO0_PMR1C (AVR32_GPIO0_BASE+AVR32_GPIO_PMR1C_OFFSET)
+#define AVR32_GPIO0_PMR1T (AVR32_GPIO0_BASE+AVR32_GPIO_PMR1T_OFFSET)
+#define AVR32_GPIO0_ODER (AVR32_GPIO0_BASE+AVR32_GPIO_ODER_OFFSET)
+#define AVR32_GPIO0_ODERS (AVR32_GPIO0_BASE+AVR32_GPIO_ODERS_OFFSET)
+#define AVR32_GPIO0_ODERC (AVR32_GPIO0_BASE+AVR32_GPIO_ODERC_OFFSET)
+#define AVR32_GPIO0_ODERT (AVR32_GPIO0_BASE+AVR32_GPIO_ODERT_OFFSET)
+#define AVR32_GPIO0_OVR (AVR32_GPIO0_BASE+AVR32_GPIO_OVR_OFFSET)
+#define AVR32_GPIO0_OVRS (AVR32_GPIO0_BASE+AVR32_GPIO_OVRS_OFFSET)
+#define AVR32_GPIO0_OVRC (AVR32_GPIO0_BASE+AVR32_GPIO_OVRC_OFFSET)
+#define AVR32_GPIO0_OVRT (AVR32_GPIO0_BASE+AVR32_GPIO_OVRT_OFFSET)
+#define AVR32_GPIO0_PVR (AVR32_GPIO0_BASE+AVR32_GPIO_PVR_OFFSET)
+#define AVR32_GPIO0_PUER (AVR32_GPIO0_BASE+AVR32_GPIO_PUER_OFFSET)
+#define AVR32_GPIO0_PUERS (AVR32_GPIO0_BASE+AVR32_GPIO_PUERS_OFFSET)
+#define AVR32_GPIO0_PUERC (AVR32_GPIO0_BASE+AVR32_GPIO_PUERC_OFFSET)
+#define AVR32_GPIO0_PUERT (AVR32_GPIO0_BASE+AVR32_GPIO_PUERT_OFFSET)
+#define AVR32_GPIO0_IER (AVR32_GPIO0_BASE+AVR32_GPIO_IER_OFFSET)
+#define AVR32_GPIO0_IERS (AVR32_GPIO0_BASE+AVR32_GPIO_IERS_OFFSET)
+#define AVR32_GPIO0_IERC (AVR32_GPIO0_BASE+AVR32_GPIO_IERC_OFFSET)
+#define AVR32_GPIO0_IERT (AVR32_GPIO0_BASE+AVR32_GPIO_IERT_OFFSET)
+#define AVR32_GPIO0_IMR0 (AVR32_GPIO0_BASE+AVR32_GPIO_IMR0_OFFSET)
+#define AVR32_GPIO0_IMR0S (AVR32_GPIO0_BASE+AVR32_GPIO_IMR0S_OFFSET)
+#define AVR32_GPIO0_IMR0C (AVR32_GPIO0_BASE+AVR32_GPIO_IMR0C_OFFSET)
+#define AVR32_GPIO0_IMR0T (AVR32_GPIO0_BASE+AVR32_GPIO_IMR0T_OFFSET)
+#define AVR32_GPIO0_IMR1 (AVR32_GPIO0_BASE+AVR32_GPIO_IMR1_OFFSET)
+#define AVR32_GPIO0_IMR1S (AVR32_GPIO0_BASE+AVR32_GPIO_IMR1S_OFFSET)
+#define AVR32_GPIO0_IMR1C (AVR32_GPIO0_BASE+AVR32_GPIO_IMR1C_OFFSET)
+#define AVR32_GPIO0_IMR1T (AVR32_GPIO0_BASE+AVR32_GPIO_IMR1T_OFFSET)
+#define AVR32_GPIO0_GFER (AVR32_GPIO0_BASE+AVR32_GPIO_GFER_OFFSET)
+#define AVR32_GPIO0_GFERS (AVR32_GPIO0_BASE+AVR32_GPIO_GFERS_OFFSET)
+#define AVR32_GPIO0_GFERC (AVR32_GPIO0_BASE+AVR32_GPIO_GFERC_OFFSET)
+#define AVR32_GPIO0_GFERT (AVR32_GPIO0_BASE+AVR32_GPIO_GFERT_OFFSET)
+#define AVR32_GPIO0_IFR (AVR32_GPIO0_BASE+AVR32_GPIO_IFR_OFFSET)
+#define AVR32_GPIO0_IFRC (AVR32_GPIO0_BASE+AVR32_GPIO_IFRC_OFFSET)
+
+#define AVR32_GPIO1_GPER (AVR32_GPIO1_BASE+AVR32_GPIO_GPER_OFFSET)
+#define AVR32_GPIO1_GPERS (AVR32_GPIO1_BASE+AVR32_GPIO_GPERS_OFFSET)
+#define AVR32_GPIO1_GPERC (AVR32_GPIO1_BASE+AVR32_GPIO_GPERC_OFFSET)
+#define AVR32_GPIO1_GPERT (AVR32_GPIO1_BASE+AVR32_GPIO_GPERT_OFFSET)
+#define AVR32_GPIO1_PMR0 (AVR32_GPIO1_BASE+AVR32_GPIO_PMR0_OFFSET)
+#define AVR32_GPIO1_PMR0S (AVR32_GPIO1_BASE+AVR32_GPIO_PMR0S_OFFSET)
+#define AVR32_GPIO1_PMR0C (AVR32_GPIO1_BASE+AVR32_GPIO_PMR0C_OFFSET)
+#define AVR32_GPIO1_PMR0T (AVR32_GPIO1_BASE+AVR32_GPIO_PMR0T_OFFSET)
+#define AVR32_GPIO1_PMR1 (AVR32_GPIO1_BASE+AVR32_GPIO_PMR1_OFFSET)
+#define AVR32_GPIO1_PMR1S (AVR32_GPIO1_BASE+AVR32_GPIO_PMR1S_OFFSET)
+#define AVR32_GPIO1_PMR1C (AVR32_GPIO1_BASE+AVR32_GPIO_PMR1C_OFFSET)
+#define AVR32_GPIO1_PMR1T (AVR32_GPIO1_BASE+AVR32_GPIO_PMR1T_OFFSET)
+#define AVR32_GPIO1_ODER (AVR32_GPIO1_BASE+AVR32_GPIO_ODER_OFFSET)
+#define AVR32_GPIO1_ODERS (AVR32_GPIO1_BASE+AVR32_GPIO_ODERS_OFFSET)
+#define AVR32_GPIO1_ODERC (AVR32_GPIO1_BASE+AVR32_GPIO_ODERC_OFFSET)
+#define AVR32_GPIO1_ODERT (AVR32_GPIO1_BASE+AVR32_GPIO_ODERT_OFFSET)
+#define AVR32_GPIO1_OVR (AVR32_GPIO1_BASE+AVR32_GPIO_OVR_OFFSET)
+#define AVR32_GPIO1_OVRS (AVR32_GPIO1_BASE+AVR32_GPIO_OVRS_OFFSET)
+#define AVR32_GPIO1_OVRC (AVR32_GPIO1_BASE+AVR32_GPIO_OVRC_OFFSET)
+#define AVR32_GPIO1_OVRT (AVR32_GPIO1_BASE+AVR32_GPIO_OVRT_OFFSET)
+#define AVR32_GPIO1_PVR (AVR32_GPIO1_BASE+AVR32_GPIO_PVR_OFFSET)
+#define AVR32_GPIO1_PUER (AVR32_GPIO1_BASE+AVR32_GPIO_PUER_OFFSET)
+#define AVR32_GPIO1_PUERS (AVR32_GPIO1_BASE+AVR32_GPIO_PUERS_OFFSET)
+#define AVR32_GPIO1_PUERC (AVR32_GPIO1_BASE+AVR32_GPIO_PUERC_OFFSET)
+#define AVR32_GPIO1_PUERT (AVR32_GPIO1_BASE+AVR32_GPIO_PUERT_OFFSET)
+#define AVR32_GPIO1_IER (AVR32_GPIO1_BASE+AVR32_GPIO_IER_OFFSET)
+#define AVR32_GPIO1_IERS (AVR32_GPIO1_BASE+AVR32_GPIO_IERS_OFFSET)
+#define AVR32_GPIO1_IERC (AVR32_GPIO1_BASE+AVR32_GPIO_IERC_OFFSET)
+#define AVR32_GPIO1_IERT (AVR32_GPIO1_BASE+AVR32_GPIO_IERT_OFFSET)
+#define AVR32_GPIO1_IMR0 (AVR32_GPIO1_BASE+AVR32_GPIO_IMR0_OFFSET)
+#define AVR32_GPIO1_IMR0S (AVR32_GPIO1_BASE+AVR32_GPIO_IMR0S_OFFSET)
+#define AVR32_GPIO1_IMR0C (AVR32_GPIO1_BASE+AVR32_GPIO_IMR0C_OFFSET)
+#define AVR32_GPIO1_IMR0T (AVR32_GPIO1_BASE+AVR32_GPIO_IMR0T_OFFSET)
+#define AVR32_GPIO1_IMR1 (AVR32_GPIO1_BASE+AVR32_GPIO_IMR1_OFFSET)
+#define AVR32_GPIO1_IMR1S (AVR32_GPIO1_BASE+AVR32_GPIO_IMR1S_OFFSET)
+#define AVR32_GPIO1_IMR1C (AVR32_GPIO1_BASE+AVR32_GPIO_IMR1C_OFFSET)
+#define AVR32_GPIO1_IMR1T (AVR32_GPIO1_BASE+AVR32_GPIO_IMR1T_OFFSET)
+#define AVR32_GPIO1_GFER (AVR32_GPIO1_BASE+AVR32_GPIO_GFER_OFFSET)
+#define AVR32_GPIO1_GFERS (AVR32_GPIO1_BASE+AVR32_GPIO_GFERS_OFFSET)
+#define AVR32_GPIO1_GFERC (AVR32_GPIO1_BASE+AVR32_GPIO_GFERC_OFFSET)
+#define AVR32_GPIO1_GFERT (AVR32_GPIO1_BASE+AVR32_GPIO_GFERT_OFFSET)
+#define AVR32_GPIO1_IFR (AVR32_GPIO1_BASE+AVR32_GPIO_IFR_OFFSET)
+#define AVR32_GPIO1_IFRC (AVR32_GPIO1_BASE+AVR32_GPIO_IFRC_OFFSET)
+
+#define AVR32_GPIO2_GPER (AVR32_GPIO2_BASE+AVR32_GPIO_GPER_OFFSET)
+#define AVR32_GPIO2_GPERS (AVR32_GPIO2_BASE+AVR32_GPIO_GPERS_OFFSET)
+#define AVR32_GPIO2_GPERC (AVR32_GPIO2_BASE+AVR32_GPIO_GPERC_OFFSET)
+#define AVR32_GPIO2_GPERT (AVR32_GPIO2_BASE+AVR32_GPIO_GPERT_OFFSET)
+#define AVR32_GPIO2_PMR0 (AVR32_GPIO2_BASE+AVR32_GPIO_PMR0_OFFSET)
+#define AVR32_GPIO2_PMR0S (AVR32_GPIO2_BASE+AVR32_GPIO_PMR0S_OFFSET)
+#define AVR32_GPIO2_PMR0C (AVR32_GPIO2_BASE+AVR32_GPIO_PMR0C_OFFSET)
+#define AVR32_GPIO2_PMR0T (AVR32_GPIO2_BASE+AVR32_GPIO_PMR0T_OFFSET)
+#define AVR32_GPIO2_PMR1 (AVR32_GPIO2_BASE+AVR32_GPIO_PMR1_OFFSET)
+#define AVR32_GPIO2_PMR1S (AVR32_GPIO2_BASE+AVR32_GPIO_PMR1S_OFFSET)
+#define AVR32_GPIO2_PMR1C (AVR32_GPIO2_BASE+AVR32_GPIO_PMR1C_OFFSET)
+#define AVR32_GPIO2_PMR1T (AVR32_GPIO2_BASE+AVR32_GPIO_PMR1T_OFFSET)
+#define AVR32_GPIO2_ODER (AVR32_GPIO2_BASE+AVR32_GPIO_ODER_OFFSET)
+#define AVR32_GPIO2_ODERS (AVR32_GPIO2_BASE+AVR32_GPIO_ODERS_OFFSET)
+#define AVR32_GPIO2_ODERC (AVR32_GPIO2_BASE+AVR32_GPIO_ODERC_OFFSET)
+#define AVR32_GPIO2_ODERT (AVR32_GPIO2_BASE+AVR32_GPIO_ODERT_OFFSET)
+#define AVR32_GPIO2_OVR (AVR32_GPIO2_BASE+AVR32_GPIO_OVR_OFFSET)
+#define AVR32_GPIO2_OVRS (AVR32_GPIO2_BASE+AVR32_GPIO_OVRS_OFFSET)
+#define AVR32_GPIO2_OVRC (AVR32_GPIO2_BASE+AVR32_GPIO_OVRC_OFFSET)
+#define AVR32_GPIO2_OVRT (AVR32_GPIO2_BASE+AVR32_GPIO_OVRT_OFFSET)
+#define AVR32_GPIO2_PVR (AVR32_GPIO2_BASE+AVR32_GPIO_PVR_OFFSET)
+#define AVR32_GPIO2_PUER (AVR32_GPIO2_BASE+AVR32_GPIO_PUER_OFFSET)
+#define AVR32_GPIO2_PUERS (AVR32_GPIO2_BASE+AVR32_GPIO_PUERS_OFFSET)
+#define AVR32_GPIO2_PUERC (AVR32_GPIO2_BASE+AVR32_GPIO_PUERC_OFFSET)
+#define AVR32_GPIO2_PUERT (AVR32_GPIO2_BASE+AVR32_GPIO_PUERT_OFFSET)
+#define AVR32_GPIO2_IER (AVR32_GPIO2_BASE+AVR32_GPIO_IER_OFFSET)
+#define AVR32_GPIO2_IERS (AVR32_GPIO2_BASE+AVR32_GPIO_IERS_OFFSET)
+#define AVR32_GPIO2_IERC (AVR32_GPIO2_BASE+AVR32_GPIO_IERC_OFFSET)
+#define AVR32_GPIO2_IERT (AVR32_GPIO2_BASE+AVR32_GPIO_IERT_OFFSET)
+#define AVR32_GPIO2_IMR0 (AVR32_GPIO2_BASE+AVR32_GPIO_IMR0_OFFSET)
+#define AVR32_GPIO2_IMR0S (AVR32_GPIO2_BASE+AVR32_GPIO_IMR0S_OFFSET)
+#define AVR32_GPIO2_IMR0C (AVR32_GPIO2_BASE+AVR32_GPIO_IMR0C_OFFSET)
+#define AVR32_GPIO2_IMR0T (AVR32_GPIO2_BASE+AVR32_GPIO_IMR0T_OFFSET)
+#define AVR32_GPIO2_IMR1 (AVR32_GPIO2_BASE+AVR32_GPIO_IMR1_OFFSET)
+#define AVR32_GPIO2_IMR1S (AVR32_GPIO2_BASE+AVR32_GPIO_IMR1S_OFFSET)
+#define AVR32_GPIO2_IMR1C (AVR32_GPIO2_BASE+AVR32_GPIO_IMR1C_OFFSET)
+#define AVR32_GPIO2_IMR1T (AVR32_GPIO2_BASE+AVR32_GPIO_IMR1T_OFFSET)
+#define AVR32_GPIO2_GFER (AVR32_GPIO2_BASE+AVR32_GPIO_GFER_OFFSET)
+#define AVR32_GPIO2_GFERS (AVR32_GPIO2_BASE+AVR32_GPIO_GFERS_OFFSET)
+#define AVR32_GPIO2_GFERC (AVR32_GPIO2_BASE+AVR32_GPIO_GFERC_OFFSET)
+#define AVR32_GPIO2_GFERT (AVR32_GPIO2_BASE+AVR32_GPIO_GFERT_OFFSET)
+#define AVR32_GPIO2_IFR (AVR32_GPIO2_BASE+AVR32_GPIO_IFR_OFFSET)
+#define AVR32_GPIO2_IFRC (AVR32_GPIO2_BASE+AVR32_GPIO_IFRC_OFFSET)
+
+#define AVR32_GPIO3_GPER (AVR32_GPIO3_BASE+AVR32_GPIO_GPER_OFFSET)
+#define AVR32_GPIO3_GPERS (AVR32_GPIO3_BASE+AVR32_GPIO_GPERS_OFFSET)
+#define AVR32_GPIO3_GPERC (AVR32_GPIO3_BASE+AVR32_GPIO_GPERC_OFFSET)
+#define AVR32_GPIO3_GPERT (AVR32_GPIO3_BASE+AVR32_GPIO_GPERT_OFFSET)
+#define AVR32_GPIO3_PMR0 (AVR32_GPIO3_BASE+AVR32_GPIO_PMR0_OFFSET)
+#define AVR32_GPIO3_PMR0S (AVR32_GPIO3_BASE+AVR32_GPIO_PMR0S_OFFSET)
+#define AVR32_GPIO3_PMR0C (AVR32_GPIO3_BASE+AVR32_GPIO_PMR0C_OFFSET)
+#define AVR32_GPIO3_PMR0T (AVR32_GPIO3_BASE+AVR32_GPIO_PMR0T_OFFSET)
+#define AVR32_GPIO3_PMR1 (AVR32_GPIO3_BASE+AVR32_GPIO_PMR1_OFFSET)
+#define AVR32_GPIO3_PMR1S (AVR32_GPIO3_BASE+AVR32_GPIO_PMR1S_OFFSET)
+#define AVR32_GPIO3_PMR1C (AVR32_GPIO3_BASE+AVR32_GPIO_PMR1C_OFFSET)
+#define AVR32_GPIO3_PMR1T (AVR32_GPIO3_BASE+AVR32_GPIO_PMR1T_OFFSET)
+#define AVR32_GPIO3_ODER (AVR32_GPIO3_BASE+AVR32_GPIO_ODER_OFFSET)
+#define AVR32_GPIO3_ODERS (AVR32_GPIO3_BASE+AVR32_GPIO_ODERS_OFFSET)
+#define AVR32_GPIO3_ODERC (AVR32_GPIO3_BASE+AVR32_GPIO_ODERC_OFFSET)
+#define AVR32_GPIO3_ODERT (AVR32_GPIO3_BASE+AVR32_GPIO_ODERT_OFFSET)
+#define AVR32_GPIO3_OVR (AVR32_GPIO3_BASE+AVR32_GPIO_OVR_OFFSET)
+#define AVR32_GPIO3_OVRS (AVR32_GPIO3_BASE+AVR32_GPIO_OVRS_OFFSET)
+#define AVR32_GPIO3_OVRC (AVR32_GPIO3_BASE+AVR32_GPIO_OVRC_OFFSET)
+#define AVR32_GPIO3_OVRT (AVR32_GPIO3_BASE+AVR32_GPIO_OVRT_OFFSET)
+#define AVR32_GPIO3_PVR (AVR32_GPIO3_BASE+AVR32_GPIO_PVR_OFFSET)
+#define AVR32_GPIO3_PUER (AVR32_GPIO3_BASE+AVR32_GPIO_PUER_OFFSET)
+#define AVR32_GPIO3_PUERS (AVR32_GPIO3_BASE+AVR32_GPIO_PUERS_OFFSET)
+#define AVR32_GPIO3_PUERC (AVR32_GPIO3_BASE+AVR32_GPIO_PUERC_OFFSET)
+#define AVR32_GPIO3_PUERT (AVR32_GPIO3_BASE+AVR32_GPIO_PUERT_OFFSET)
+#define AVR32_GPIO3_IER (AVR32_GPIO3_BASE+AVR32_GPIO_IER_OFFSET)
+#define AVR32_GPIO3_IERS (AVR32_GPIO3_BASE+AVR32_GPIO_IERS_OFFSET)
+#define AVR32_GPIO3_IERC (AVR32_GPIO3_BASE+AVR32_GPIO_IERC_OFFSET)
+#define AVR32_GPIO3_IERT (AVR32_GPIO3_BASE+AVR32_GPIO_IERT_OFFSET)
+#define AVR32_GPIO3_IMR0 (AVR32_GPIO3_BASE+AVR32_GPIO_IMR0_OFFSET)
+#define AVR32_GPIO3_IMR0S (AVR32_GPIO3_BASE+AVR32_GPIO_IMR0S_OFFSET)
+#define AVR32_GPIO3_IMR0C (AVR32_GPIO3_BASE+AVR32_GPIO_IMR0C_OFFSET)
+#define AVR32_GPIO3_IMR0T (AVR32_GPIO3_BASE+AVR32_GPIO_IMR0T_OFFSET)
+#define AVR32_GPIO3_IMR1 (AVR32_GPIO3_BASE+AVR32_GPIO_IMR1_OFFSET)
+#define AVR32_GPIO3_IMR1S (AVR32_GPIO3_BASE+AVR32_GPIO_IMR1S_OFFSET)
+#define AVR32_GPIO3_IMR1C (AVR32_GPIO3_BASE+AVR32_GPIO_IMR1C_OFFSET)
+#define AVR32_GPIO3_IMR1T (AVR32_GPIO3_BASE+AVR32_GPIO_IMR1T_OFFSET)
+#define AVR32_GPIO3_GFER (AVR32_GPIO3_BASE+AVR32_GPIO_GFER_OFFSET)
+#define AVR32_GPIO3_GFERS (AVR32_GPIO3_BASE+AVR32_GPIO_GFERS_OFFSET)
+#define AVR32_GPIO3_GFERC (AVR32_GPIO3_BASE+AVR32_GPIO_GFERC_OFFSET)
+#define AVR32_GPIO3_GFERT (AVR32_GPIO3_BASE+AVR32_GPIO_GFERT_OFFSET)
+#define AVR32_GPIO3_IFR (AVR32_GPIO3_BASE+AVR32_GPIO_IFR_OFFSET)
+#define AVR32_GPIO3_IFRC (AVR32_GPIO3_BASE+AVR32_GPIO_IFRC_OFFSET)
+
+#define AVR32_GPIO4_GPER (AVR32_GPIO4_BASE+AVR32_GPIO_GPER_OFFSET)
+#define AVR32_GPIO4_GPERS (AVR32_GPIO4_BASE+AVR32_GPIO_GPERS_OFFSET)
+#define AVR32_GPIO4_GPERC (AVR32_GPIO4_BASE+AVR32_GPIO_GPERC_OFFSET)
+#define AVR32_GPIO4_GPERT (AVR32_GPIO4_BASE+AVR32_GPIO_GPERT_OFFSET)
+#define AVR32_GPIO4_PMR0 (AVR32_GPIO4_BASE+AVR32_GPIO_PMR0_OFFSET)
+#define AVR32_GPIO4_PMR0S (AVR32_GPIO4_BASE+AVR32_GPIO_PMR0S_OFFSET)
+#define AVR32_GPIO4_PMR0C (AVR32_GPIO4_BASE+AVR32_GPIO_PMR0C_OFFSET)
+#define AVR32_GPIO4_PMR0T (AVR32_GPIO4_BASE+AVR32_GPIO_PMR0T_OFFSET)
+#define AVR32_GPIO4_PMR1 (AVR32_GPIO4_BASE+AVR32_GPIO_PMR1_OFFSET)
+#define AVR32_GPIO4_PMR1S (AVR32_GPIO4_BASE+AVR32_GPIO_PMR1S_OFFSET)
+#define AVR32_GPIO4_PMR1C (AVR32_GPIO4_BASE+AVR32_GPIO_PMR1C_OFFSET)
+#define AVR32_GPIO4_PMR1T (AVR32_GPIO4_BASE+AVR32_GPIO_PMR1T_OFFSET)
+#define AVR32_GPIO4_ODER (AVR32_GPIO4_BASE+AVR32_GPIO_ODER_OFFSET)
+#define AVR32_GPIO4_ODERS (AVR32_GPIO4_BASE+AVR32_GPIO_ODERS_OFFSET)
+#define AVR32_GPIO4_ODERC (AVR32_GPIO4_BASE+AVR32_GPIO_ODERC_OFFSET)
+#define AVR32_GPIO4_ODERT (AVR32_GPIO4_BASE+AVR32_GPIO_ODERT_OFFSET)
+#define AVR32_GPIO4_OVR (AVR32_GPIO4_BASE+AVR32_GPIO_OVR_OFFSET)
+#define AVR32_GPIO4_OVRS (AVR32_GPIO4_BASE+AVR32_GPIO_OVRS_OFFSET)
+#define AVR32_GPIO4_OVRC (AVR32_GPIO4_BASE+AVR32_GPIO_OVRC_OFFSET)
+#define AVR32_GPIO4_OVRT (AVR32_GPIO4_BASE+AVR32_GPIO_OVRT_OFFSET)
+#define AVR32_GPIO4_PVR (AVR32_GPIO4_BASE+AVR32_GPIO_PVR_OFFSET)
+#define AVR32_GPIO4_PUER (AVR32_GPIO4_BASE+AVR32_GPIO_PUER_OFFSET)
+#define AVR32_GPIO4_PUERS (AVR32_GPIO4_BASE+AVR32_GPIO_PUERS_OFFSET)
+#define AVR32_GPIO4_PUERC (AVR32_GPIO4_BASE+AVR32_GPIO_PUERC_OFFSET)
+#define AVR32_GPIO4_PUERT (AVR32_GPIO4_BASE+AVR32_GPIO_PUERT_OFFSET)
+#define AVR32_GPIO4_IER (AVR32_GPIO4_BASE+AVR32_GPIO_IER_OFFSET)
+#define AVR32_GPIO4_IERS (AVR32_GPIO4_BASE+AVR32_GPIO_IERS_OFFSET)
+#define AVR32_GPIO4_IERC (AVR32_GPIO4_BASE+AVR32_GPIO_IERC_OFFSET)
+#define AVR32_GPIO4_IERT (AVR32_GPIO4_BASE+AVR32_GPIO_IERT_OFFSET)
+#define AVR32_GPIO4_IMR0 (AVR32_GPIO4_BASE+AVR32_GPIO_IMR0_OFFSET)
+#define AVR32_GPIO4_IMR0S (AVR32_GPIO4_BASE+AVR32_GPIO_IMR0S_OFFSET)
+#define AVR32_GPIO4_IMR0C (AVR32_GPIO4_BASE+AVR32_GPIO_IMR0C_OFFSET)
+#define AVR32_GPIO4_IMR0T (AVR32_GPIO4_BASE+AVR32_GPIO_IMR0T_OFFSET)
+#define AVR32_GPIO4_IMR1 (AVR32_GPIO4_BASE+AVR32_GPIO_IMR1_OFFSET)
+#define AVR32_GPIO4_IMR1S (AVR32_GPIO4_BASE+AVR32_GPIO_IMR1S_OFFSET)
+#define AVR32_GPIO4_IMR1C (AVR32_GPIO4_BASE+AVR32_GPIO_IMR1C_OFFSET)
+#define AVR32_GPIO4_IMR1T (AVR32_GPIO4_BASE+AVR32_GPIO_IMR1T_OFFSET)
+#define AVR32_GPIO4_GFER (AVR32_GPIO4_BASE+AVR32_GPIO_GFER_OFFSET)
+#define AVR32_GPIO4_GFERS (AVR32_GPIO4_BASE+AVR32_GPIO_GFERS_OFFSET)
+#define AVR32_GPIO4_GFERC (AVR32_GPIO4_BASE+AVR32_GPIO_GFERC_OFFSET)
+#define AVR32_GPIO4_GFERT (AVR32_GPIO4_BASE+AVR32_GPIO_GFERT_OFFSET)
+#define AVR32_GPIO4_IFR (AVR32_GPIO4_BASE+AVR32_GPIO_IFR_OFFSET)
+#define AVR32_GPIO4_IFRC (AVR32_GPIO4_BASE+AVR32_GPIO_IFRC_OFFSET)
+
+/* Local bus mapped GPIO registers */
+
+#define AVR32_GPIO0_LBUS_ODER (AVR32_GPIO0_LBUS_BASE+AVR32_GPIO_ODER_OFFSET)
+#define AVR32_GPIO0_LBUS_ODERS (AVR32_GPIO0_LBUS_BASE+AVR32_GPIO_ODERS_OFFSET)
+#define AVR32_GPIO0_LBUS_ODERC (AVR32_GPIO0_LBUS_BASE+AVR32_GPIO_ODERC_OFFSET)
+#define AVR32_GPIO0_LBUS_ODERT (AVR32_GPIO0_LBUS_BASE+AVR32_GPIO_ODERT_OFFSET)
+#define AVR32_GPIO0_LBUS_OVR (AVR32_GPIO0_LBUS_BASE+AVR32_GPIO_OVR_OFFSET)
+#define AVR32_GPIO0_LBUS_OVRS (AVR32_GPIO0_LBUS_BASE+AVR32_GPIO_OVRS_OFFSET)
+#define AVR32_GPIO0_LBUS_OVRC (AVR32_GPIO0_LBUS_BASE+AVR32_GPIO_OVRC_OFFSET)
+#define AVR32_GPIO0_LBUS_OVRT (AVR32_GPIO0_LBUS_BASE+AVR32_GPIO_OVRT_OFFSET)
+#define AVR32_GPIO0_LBUS_PVR (AVR32_GPIO0_LBUS_BASE+AVR32_GPIO_PVR_OFFSET)
+
+#define AVR32_GPIO1_LBUS_ODER (AVR32_GPIO1_LBUS_BASE+AVR32_GPIO_ODER_OFFSET)
+#define AVR32_GPIO1_LBUS_ODERS (AVR32_GPIO1_LBUS_BASE+AVR32_GPIO_ODERS_OFFSET)
+#define AVR32_GPIO1_LBUS_ODERC (AVR32_GPIO1_LBUS_BASE+AVR32_GPIO_ODERC_OFFSET)
+#define AVR32_GPIO1_LBUS_ODERT (AVR32_GPIO1_LBUS_BASE+AVR32_GPIO_ODERT_OFFSET)
+#define AVR32_GPIO1_LBUS_OVR (AVR32_GPIO1_LBUS_BASE+AVR32_GPIO_OVR_OFFSET)
+#define AVR32_GPIO1_LBUS_OVRS (AVR32_GPIO1_LBUS_BASE+AVR32_GPIO_OVRS_OFFSET)
+#define AVR32_GPIO1_LBUS_OVRC (AVR32_GPIO1_LBUS_BASE+AVR32_GPIO_OVRC_OFFSET)
+#define AVR32_GPIO1_LBUS_OVRT (AVR32_GPIO1_LBUS_BASE+AVR32_GPIO_OVRT_OFFSET)
+#define AVR32_GPIO1_LBUS_PVR (AVR32_GPIO1_LBUS_BASE+AVR32_GPIO_PVR_OFFSET)
+
+/* Register Bit-field Definitions ***************************************************/
+
+/* For all registers, there are 32 bits, each associated with one pin on the port. */
+
+#define GPIO_PIN(n) (1 << (n))
+#define GPIO_PIN0 (1 << 0)
+#define GPIO_PIN1 (1 << 1)
+#define GPIO_PIN2 (1 << 2)
+#define GPIO_PIN3 (1 << 3)
+#define GPIO_PIN4 (1 << 4)
+#define GPIO_PIN5 (1 << 5)
+#define GPIO_PIN6 (1 << 6)
+#define GPIO_PIN7 (1 << 7)
+#define GPIO_PIN8 (1 << 8)
+#define GPIO_PIN9 (1 << 9)
+#define GPIO_PIN10 (1 << 10)
+#define GPIO_PIN11 (1 << 11)
+#define GPIO_PIN12 (1 << 12)
+#define GPIO_PIN13 (1 << 13)
+#define GPIO_PIN14 (1 << 14)
+#define GPIO_PIN15 (1 << 15)
+#define GPIO_PIN16 (1 << 16)
+#define GPIO_PIN17 (1 << 17)
+#define GPIO_PIN18 (1 << 18)
+#define GPIO_PIN19 (1 << 19)
+#define GPIO_PIN20 (1 << 20)
+#define GPIO_PIN21 (1 << 21)
+#define GPIO_PIN22 (1 << 22)
+#define GPIO_PIN23 (1 << 23)
+#define GPIO_PIN24 (1 << 24)
+#define GPIO_PIN25 (1 << 25)
+#define GPIO_PIN26 (1 << 26)
+#define GPIO_PIN27 (1 << 27)
+#define GPIO_PIN28 (1 << 28)
+#define GPIO_PIN29 (1 << 29)
+#define GPIO_PIN30 (1 << 30)
+#define GPIO_PIN31 (1 << 31)
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_AVR_SRC_AT32UC3_AT32UC3_GPIO_H */
+
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_gpioirq.c b/nuttx/arch/avr/src/at32uc3/at32uc3_gpioirq.c
new file mode 100644
index 000000000..0e05bf02a
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_gpioirq.c
@@ -0,0 +1,428 @@
+/****************************************************************************
+ * arch/avr/src/at32uc3/at32uc3_gpioirq.c
+ * arch/avr/src/chip/at32uc3_gpioirq.c
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include "at32uc3_config.h"
+
+#include <stdint.h>
+#include <string.h>
+#include <assert.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <arch/irq.h>
+
+#include "up_arch.h"
+#include "os_internal.h"
+#include "irq_internal.h"
+#include "at32uc3_internal.h"
+#include "at32uc3_gpio.h"
+
+#ifdef CONFIG_AVR32_GPIOIRQ
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/* A table of handlers for each GPIO interrupt */
+
+static FAR xcpt_t g_gpiohandler[NR_GPIO_IRQS];
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: gpio_baseaddress
+ *
+ * Input:
+ * irq - A IRQ number in the range of 0 to NR_GPIO_IRQS.
+ *
+ * Description:
+ * Given a IRQ number, return the base address of the associated GPIO
+ * registers.
+ *
+ ****************************************************************************/
+
+static inline uint32_t gpio_baseaddress(unsigned int irq)
+{
+#if CONFIG_AVR32_GPIOIRQSETA != 0
+ if (irq < __IRQ_GPIO_PB0)
+ {
+ return AVR32_GPIO0_BASE;
+ }
+ else
+#endif
+#if CONFIG_AVR32_GPIOIRQSETB != 0
+ if (irq < NR_GPIO_IRQS)
+ {
+ return AVR32_GPIO1_BASE;
+ }
+ else
+#endif
+ {
+ return 0;
+ }
+}
+
+/****************************************************************************
+ * Name: gpio_pin
+ *
+ * Input:
+ * irq - A IRQ number in the range of 0 to NR_GPIO_IRQS.
+ *
+ * Description:
+ * Given a GPIO number, return the pin number in the range of 0-31 on the
+ * corresponding port
+ *
+ ****************************************************************************/
+
+static inline int gpio_pin(unsigned int irq)
+{
+ uint32_t pinset;
+ int pinirq;
+ int pin;
+
+#if CONFIG_AVR32_GPIOIRQSETA != 0
+ if (irq < __IRQ_GPIO_PB0)
+ {
+ pinset = CONFIG_AVR32_GPIOIRQSETA;
+ pinirq = __IRQ_GPIO_PA0;
+ }
+ else
+#endif
+#if CONFIG_AVR32_GPIOIRQSETB != 0
+ if (irq < NR_GPIO_IRQS)
+ {
+ pinset = CONFIG_AVR32_GPIOIRQSETB;
+ pinirq = __IRQ_GPIO_PB0;
+ }
+ else
+#endif
+ {
+ return -EINVAL;
+ }
+
+ /* Now we have to search for the pin with matching IRQ. Yech! We made
+ * life difficult here by choosing a sparse representation of IRQs on
+ * GPIO pins.
+ */
+
+ for (pin = 0; pin < 32 && pinset != 0; pin++)
+ {
+ /* Is this pin at bit 0 configured for interrupt support? */
+
+ if ((pinset & 1) != 0)
+ {
+ /* Is it the on IRQ we are looking for? */
+
+ if (pinirq == irq)
+ {
+ /* Yes, return the associated pin number */
+
+ return pin;
+ }
+
+ /* No.. Increment the IRQ number for the next configured pin */
+
+ pinirq++;
+ }
+
+ /* Shift the next pin to position bit 0 */
+
+ pinset >>= 1;
+ }
+
+ return -EINVAL;
+}
+
+/****************************************************************************
+ * Name: gpio_porthandler
+ *
+ * Description:
+ * Dispatch GPIO interrupts on a specific GPIO port
+ *
+ ****************************************************************************/
+
+static void gpio_porthandler(uint32_t regbase, int irqbase, uint32_t irqset, void *context)
+{
+ uint32_t ifr;
+ int irq;
+ int pin;
+
+ /* Check each bit and dispatch each pending interrupt in the interrupt flag
+ * register for this port.
+ */
+
+ ifr = getreg32(regbase + AVR32_GPIO_IFR_OFFSET);
+
+ /* Dispatch each pending interrupt */
+
+ irq = irqbase;
+ for (pin = 0; pin < 32 && ifr != 0; pin++)
+ {
+ /* Is this pin configured for interrupt support? */
+
+ uint32_t bit = (1 << pin);
+ if ((irqset & bit) != 0)
+ {
+ /* Is an interrupt pending on this pin? */
+
+ if ((ifr & bit) != 0)
+ {
+ /* Yes.. Clear the pending interrupt */
+
+ putreg32(bit, regbase + AVR32_GPIO_IFRC_OFFSET);
+ ifr &= ~bit;
+
+ /* Dispatch handling for this pin */
+
+ xcpt_t handler = g_gpiohandler[irq];
+ if (handler)
+ {
+ handler(irq, context);
+ }
+ else
+ {
+ lldbg("No handler: pin=%d ifr=%08x irqset=%08x",
+ pin, ifr, irqset);
+ }
+ }
+
+ /* Increment the IRQ number on all configured pins */
+
+ irq++;
+ }
+
+ /* Not configured. An interrupt on this pin would be an error. */
+
+ else if ((ifr & bit) != 0)
+ {
+ /* Clear the pending interrupt */
+
+ putreg32(bit, regbase + AVR32_GPIO_IFRC_OFFSET);
+ ifr &= ~bit;
+
+ lldbg("IRQ on unconfigured pin: pin=%d ifr=%08x irqset=%08x",
+ pin, ifr, irqset);
+ }
+ }
+}
+
+/****************************************************************************
+ * Name: gpio0/1_interrupt
+ *
+ * Description:
+ * Handle GPIO0/1 interrupts
+ *
+ ****************************************************************************/
+
+#if CONFIG_AVR32_GPIOIRQSETA != 0
+static int gpio0_interrupt(int irq, FAR void *context)
+{
+ gpio_porthandler(AVR32_GPIO0_BASE, __IRQ_GPIO_PA0,
+ CONFIG_AVR32_GPIOIRQSETA, context);
+ return 0;
+}
+#endif
+
+#if CONFIG_AVR32_GPIOIRQSETB != 0
+static int gpio1_interrupt(int irq, FAR void *context)
+{
+ gpio_porthandler(AVR32_GPIO1_BASE, __IRQ_GPIO_PB0,
+ CONFIG_AVR32_GPIOIRQSETB, context);
+
+ return 0;
+}
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: gpio_irqinitialize
+ *
+ * Description:
+ * Initialize all vectors to the unexpected interrupt handler.
+ *
+ * Assumptions:
+ * Called during the early boot sequence before global interrupts have
+ * been enabled.
+ *
+ ****************************************************************************/
+
+void gpio_irqinitialize(void)
+{
+ int i;
+
+ /* Point all interrupt vectors to the unexpected interrupt */
+
+ for (i = 0; i < NR_GPIO_IRQS; i++)
+ {
+ g_gpiohandler[i] = irq_unexpected_isr;
+ }
+
+ /* Then attach the GPIO interrupt handlers */
+
+#if CONFIG_AVR32_GPIOIRQSETA != 0
+ irq_attach(AVR32_IRQ_GPIO0, gpio0_interrupt);
+#endif
+#if CONFIG_AVR32_GPIOIRQSETB != 0
+ irq_attach(AVR32_IRQ_GPIO1, gpio1_interrupt);
+#endif
+}
+
+/****************************************************************************
+ * Name: gpio_irqattach
+ *
+ * Description:
+ * Attach in GPIO interrupt to the provide 'isr'
+ *
+ ****************************************************************************/
+
+int gpio_irqattach(int irq, xcpt_t newisr, xcpt_t *oldisr)
+{
+ irqstate_t flags;
+ int ret = -EINVAL;
+
+ if ((unsigned)irq < NR_GPIO_IRQS)
+ {
+ /* If the new ISR is NULL, then the ISR is being detached. In this
+ * case, disable the ISR and direct any interrupts
+ * to the unexpected interrupt handler.
+ */
+
+ flags = irqsave();
+ if (newisr == NULL)
+ {
+ gpio_irqdisable(irq);
+ newisr = irq_unexpected_isr;
+ }
+
+ /* Return the old ISR (in case the caller ever wants to restore it) */
+
+ if (oldisr)
+ {
+ *oldisr = g_gpiohandler[irq];
+ }
+
+ /* Then save the new ISR in the table. */
+
+ g_gpiohandler[irq] = newisr;
+ irqrestore(flags);
+ ret = OK;
+ }
+ return ret;
+}
+
+/****************************************************************************
+ * Name: gpio_irqenable
+ *
+ * Description:
+ * Enable the GPIO IRQ specified by 'irq'
+ *
+ ****************************************************************************/
+
+void gpio_irqenable(int irq)
+{
+ uint32_t base;
+ int pin;
+
+ if ((unsigned)irq < NR_GPIO_IRQS)
+ {
+ /* Get the base address of the GPIO module associated with this IRQ */
+
+ base = gpio_baseaddress(irq);
+
+ /* Get the pin number associated with this IRQ. We made life difficult
+ * here by choosing a sparse representation of IRQs on GPIO pins.
+ */
+
+ pin = gpio_pin(irq);
+ DEBUGASSERT(pin >= 0);
+
+ /* Enable the GPIO interrupt. */
+
+ putreg32((1 << pin), base + AVR32_GPIO_IERS_OFFSET);
+ }
+}
+
+/****************************************************************************
+ * Name: gpio_irqdisable
+ *
+ * Description:
+ * Disable the GPIO IRQ specified by 'irq'
+ *
+ ****************************************************************************/
+
+void gpio_irqdisable(int irq)
+{
+ uint32_t base;
+ int pin;
+
+ if ((unsigned)irq < NR_GPIO_IRQS)
+ {
+ /* Get the base address of the GPIO module associated with this IRQ */
+
+ base = gpio_baseaddress(irq);
+
+ /* Get the pin number associated with this IRQ. We made life difficult
+ * here by choosing a sparse representation of IRQs on GPIO pins.
+ */
+
+ pin = gpio_pin(irq);
+ DEBUGASSERT(pin >= 0);
+
+ /* Disable the GPIO interrupt. */
+
+ putreg32((1 << pin), base + AVR32_GPIO_IERC_OFFSET);
+ }
+}
+
+#endif /* CONFIG_AVR32_GPIOIRQ */
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_hmatrix.h b/nuttx/arch/avr/src/at32uc3/at32uc3_hmatrix.h
new file mode 100644
index 000000000..6190fe3de
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_hmatrix.h
@@ -0,0 +1,314 @@
+/************************************************************************************
+ * arch/avr/src/at32uc3/at32uc3_hmatrix.h
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_AVR_SRC_AT32UC3_AT32UC3_HMATRIX_H
+#define __ARCH_AVR_SRC_AT32UC3_AT32UC3_HMATRIX_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+
+#define AVR32_HMATRIX_MCFG_OFFSET(n) (0x0000+((n)<<2))
+#define AVR32_HMATRIX_MCFG0_OFFSET 0x0000 /* Master Configuration Register 0 */
+#define AVR32_HMATRIX_MCFG1_OFFSET 0x0004 /* Master Configuration Register 1 */
+#define AVR32_HMATRIX_MCFG2_OFFSET 0x0008 /* Master Configuration Register 2 */
+#define AVR32_HMATRIX_MCFG3_OFFSET 0x000c /* Master Configuration Register 3 */
+#define AVR32_HMATRIX_MCFG4_OFFSET 0x0010 /* Master Configuration Register 4 */
+#define AVR32_HMATRIX_MCFG5_OFFSET 0x0014 /* Master Configuration Register 5 */
+#define AVR32_HMATRIX_MCFG6_OFFSET 0x0018 /* Master Configuration Register 6 */
+#define AVR32_HMATRIX_MCFG7_OFFSET 0x001c /* Master Configuration Register 7 */
+#define AVR32_HMATRIX_MCFG8_OFFSET 0x0020 /* Master Configuration Register 8 */
+#define AVR32_HMATRIX_MCFG9_OFFSET 0x0024 /* Master Configuration Register 9 */
+#define AVR32_HMATRIX_MCFG10_OFFSET 0x0028 /* Master Configuration Register 10 */
+#define AVR32_HMATRIX_MCFG11_OFFSET 0x002c /* Master Configuration Register 11 */
+#define AVR32_HMATRIX_MCFG12_OFFSET 0x0030 /* Master Configuration Register 12 */
+#define AVR32_HMATRIX_MCFG13_OFFSET 0x0034 /* Master Configuration Register 13 */
+#define AVR32_HMATRIX_MCFG14_OFFSET 0x0038 /* Master Configuration Register 14 */
+#define AVR32_HMATRIX_MCFG15_OFFSET 0x003c /* Master Configuration Register 15 */
+
+#define AVR32_HMATRIX_SCFG_OFFSET(n) (0x0040+((n)<<2))
+#define AVR32_HMATRIX_SCFG0_OFFSET 0x0040 /* Slave Configuration Register 0 */
+#define AVR32_HMATRIX_SCFG1_OFFSET 0x0044 /* Slave Configuration Register 1 */
+#define AVR32_HMATRIX_SCFG2_OFFSET 0x0048 /* Slave Configuration Register 2 */
+#define AVR32_HMATRIX_SCFG3_OFFSET 0x004c /* Slave Configuration Register 3 */
+#define AVR32_HMATRIX_SCFG4_OFFSET 0x0050 /* Slave Configuration Register 4 */
+#define AVR32_HMATRIX_SCFG5_OFFSET 0x0054 /* Slave Configuration Register 5 */
+#define AVR32_HMATRIX_SCFG6_OFFSET 0x0058 /* Slave Configuration Register 6 */
+#define AVR32_HMATRIX_SCFG7_OFFSET 0x005c /* Slave Configuration Register 7 */
+#define AVR32_HMATRIX_SCFG8_OFFSET 0x0060 /* Slave Configuration Register 8 */
+#define AVR32_HMATRIX_SCFG9_OFFSET 0x0064 /* Slave Configuration Register 9 */
+#define AVR32_HMATRIX_SCFG10_OFFSET 0x0068 /* Slave Configuration Register 10 */
+#define AVR32_HMATRIX_SCFG11_OFFSET 0x006c /* Slave Configuration Register 11 */
+#define AVR32_HMATRIX_SCFG12_OFFSET 0x0070 /* Slave Configuration Register 12 */
+#define AVR32_HMATRIX_SCFG13_OFFSET 0x0074 /* Slave Configuration Register 13 */
+#define AVR32_HMATRIX_SCFG14_OFFSET 0x0078 /* Slave Configuration Register 14 */
+#define AVR32_HMATRIX_SCFG15_OFFSET 0x007c /* Slave Configuration Register 15 */
+
+#define AVR32_HMATRIX_PRAS_OFFSET(n) (0x0080+((n)<<3))
+#define AVR32_HMATRIX_PRBS_OFFSET(n) (0x0084+((n)<<3))
+#define AVR32_HMATRIX_PRAS0_OFFSET 0x0080 /* Priority Register A for Slave 0 */
+#define AVR32_HMATRIX_PRBS0_OFFSET 0x0084 /* Priority Register B for Slave 0 */
+#define AVR32_HMATRIX_PRAS1_OFFSET 0x0088 /* Priority Register A for Slave 1 */
+#define AVR32_HMATRIX_PRBS1_OFFSET 0x008c /* Priority Register B for Slave 1 */
+#define AVR32_HMATRIX_PRAS2_OFFSET 0x0090 /* Priority Register A for Slave 2 */
+#define AVR32_HMATRIX_PRBS2_OFFSET 0x0094 /* Priority Register B for Slave 2 */
+#define AVR32_HMATRIX_PRAS3_OFFSET 0x0098 /* Priority Register A for Slave 3 */
+#define AVR32_HMATRIX_PRBS3_OFFSET 0x009c /* Priority Register B for Slave 3 */
+#define AVR32_HMATRIX_PRAS4_OFFSET 0x00a0 /* Priority Register A for Slave 4 */
+#define AVR32_HMATRIX_PRBS4_OFFSET 0x00a4 /* Priority Register B for Slave 4 */
+#define AVR32_HMATRIX_PRAS5_OFFSET 0x00a8 /* Priority Register A for Slave 5 */
+#define AVR32_HMATRIX_PRBS5_OFFSET 0x00ac /* Priority Register B for Slave 5 */
+#define AVR32_HMATRIX_PRAS6_OFFSET 0x00b0 /* Priority Register A for Slave 6 */
+#define AVR32_HMATRIX_PRBS6_OFFSET 0x00b4 /* Priority Register B for Slave 6 */
+#define AVR32_HMATRIX_PRAS7_OFFSET 0x00b8 /* Priority Register A for Slave 7 */
+#define AVR32_HMATRIX_PRBS7_OFFSET 0x00bc /* Priority Register B for Slave 7 */
+#define AVR32_HMATRIX_PRAS8_OFFSET 0x00c0 /* Priority Register A for Slave 8 */
+#define AVR32_HMATRIX_PRBS8_OFFSET 0x00c4 /* Priority Register B for Slave 8 */
+#define AVR32_HMATRIX_PRAS9_OFFSET 0x00c8 /* Priority Register A for Slave 9 */
+#define AVR32_HMATRIX_PRBS9_OFFSET 0x00cc /* Priority Register B for Slave 9 */
+#define AVR32_HMATRIX_PRAS10_OFFSET 0x00d0 /* Priority Register A for Slave 10 */
+#define AVR32_HMATRIX_PRBS10_OFFSET 0x00d4 /* Priority Register B for Slave 10 */
+#define AVR32_HMATRIX_PRAS11_OFFSET 0x00d8 /* Priority Register A for Slave 11 */
+#define AVR32_HMATRIX_PRBS11_OFFSET 0x00dc /* Priority Register B for Slave 11 */
+#define AVR32_HMATRIX_PRAS12_OFFSET 0x00e0 /* Priority Register A for Slave 12 */
+#define AVR32_HMATRIX_PRBS12_OFFSET 0x00e4 /* Priority Register B for Slave 12 */
+#define AVR32_HMATRIX_PRAS13_OFFSET 0x00e8 /* Priority Register A for Slave 13 */
+#define AVR32_HMATRIX_PRBS13_OFFSET 0x00ec /* Priority Register B for Slave 13 */
+#define AVR32_HMATRIX_PRAS14_OFFSET 0x00f0 /* Priority Register A for Slave 14 */
+#define AVR32_HMATRIX_PRBS14_OFFSET 0x00f4 /* Priority Register B for Slave 14 */
+#define AVR32_HMATRIX_PRAS15_OFFSET 0x00f8 /* Priority Register A for Slave 15 */
+#define AVR32_HMATRIX_PRBS15_OFFSET 0x00fc /* Priority Register B for Slave 15 */
+
+#define AVR32_HMATRIX_SFR_OFFSET(n) (0x0110+((n)<<2))
+#define AVR32_HMATRIX_SFR0_OFFSET 0x0110 /* Special Function Register 0 */
+#define AVR32_HMATRIX_SFR1_OFFSET 0x0114 /* Special Function Register 1 */
+#define AVR32_HMATRIX_SFR2_OFFSET 0x0118 /* Special Function Register 2 */
+#define AVR32_HMATRIX_SFR3_OFFSET 0x011c /* Special Function Register 3 */
+#define AVR32_HMATRIX_SFR4_OFFSET 0x0120 /* Special Function Register 4 */
+#define AVR32_HMATRIX_SFR5_OFFSET 0x0124 /* Special Function Register 5 */
+#define AVR32_HMATRIX_SFR6_OFFSET 0x0128 /* Special Function Register 6 */
+#define AVR32_HMATRIX_SFR7_OFFSET 0x012c /* Special Function Register 7 */
+#define AVR32_HMATRIX_SFR8_OFFSET 0x0130 /* Special Function Register 8 */
+#define AVR32_HMATRIX_SFR9_OFFSET 0x0134 /* Special Function Register 9 */
+#define AVR32_HMATRIX_SFR10_OFFSET 0x0138 /* Special Function Register 10 */
+#define AVR32_HMATRIX_SFR11_OFFSET 0x013c /* Special Function Register 11 */
+#define AVR32_HMATRIX_SFR12_OFFSET 0x0140 /* Special Function Register 12 */
+#define AVR32_HMATRIX_SFR13_OFFSET 0x0144 /* Special Function Register 13 */
+#define AVR32_HMATRIX_SFR14_OFFSET 0x0148 /* Special Function Register 14 */
+#define AVR32_HMATRIX_SFR15_OFFSET 0x014c /* Special Function Register 15 */
+
+/* Register Addresses ***************************************************************/
+
+#define AVR32_HMATRIX_MCFG(n) (AVR32_HMATRIX_BASE+AVR32_HMATRIX_MCFG_OFFSET(n))
+#define AVR32_HMATRIX_MCFG0 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_MCFG0_OFFSET)
+#define AVR32_HMATRIX_MCFG1 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_MCFG1_OFFSET)
+#define AVR32_HMATRIX_MCFG2 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_MCFG2_OFFSET)
+#define AVR32_HMATRIX_MCFG3 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_MCFG3_OFFSET)
+#define AVR32_HMATRIX_MCFG4 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_MCFG4_OFFSET)
+#define AVR32_HMATRIX_MCFG5 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_MCFG5_OFFSET)
+#define AVR32_HMATRIX_MCFG6 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_MCFG6_OFFSET)
+#define AVR32_HMATRIX_MCFG7 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_MCFG7_OFFSET)
+#define AVR32_HMATRIX_MCFG8 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_MCFG8_OFFSET)
+#define AVR32_HMATRIX_MCFG9 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_MCFG9_OFFSET)
+#define AVR32_HMATRIX_MCFG10 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_MCFG10_OFFSET)
+#define AVR32_HMATRIX_MCFG11 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_MCFG11_OFFSET)
+#define AVR32_HMATRIX_MCFG12 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_MCFG12_OFFSET)
+#define AVR32_HMATRIX_MCFG13 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_MCFG13_OFFSET)
+#define AVR32_HMATRIX_MCFG14 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_MCFG14_OFFSET)
+#define AVR32_HMATRIX_MCFG15 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_MCFG15_OFFSET)
+
+#define AVR32_HMATRIX_SCFG(n) (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SCFG_OFFSET(n))
+#define AVR32_HMATRIX_SCFG0 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SCFG0_OFFSET)
+#define AVR32_HMATRIX_SCFG1 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SCFG1_OFFSET)
+#define AVR32_HMATRIX_SCFG2 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SCFG2_OFFSET)
+#define AVR32_HMATRIX_SCFG3 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SCFG3_OFFSET)
+#define AVR32_HMATRIX_SCFG4 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SCFG4_OFFSET)
+#define AVR32_HMATRIX_SCFG5 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SCFG5_OFFSET)
+#define AVR32_HMATRIX_SCFG6 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SCFG6_OFFSET)
+#define AVR32_HMATRIX_SCFG7 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SCFG7_OFFSET)
+#define AVR32_HMATRIX_SCFG8 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SCFG8_OFFSET)
+#define AVR32_HMATRIX_SCFG9 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SCFG9_OFFSET)
+#define AVR32_HMATRIX_SCFG10 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SCFG10_OFFSET)
+#define AVR32_HMATRIX_SCFG11 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SCFG11_OFFSET)
+#define AVR32_HMATRIX_SCFG12 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SCFG12_OFFSET)
+#define AVR32_HMATRIX_SCFG13 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SCFG13_OFFSET)
+#define AVR32_HMATRIX_SCFG14 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SCFG14_OFFSET)
+#define AVR32_HMATRIX_SCFG15 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SCFG15_OFFSET)
+
+#define AVR32_HMATRIX_PRAS(n) (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRAS_OFFSET(n))
+#define AVR32_HMATRIX_PRBS(n) (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRBS_OFFSET(n))
+#define AVR32_HMATRIX_PRAS0 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRAS0_OFFSET)
+#define AVR32_HMATRIX_PRBS0 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRBS0_OFFSET)
+#define AVR32_HMATRIX_PRAS1 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRAS1_OFFSET)
+#define AVR32_HMATRIX_PRBS1 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRBS1_OFFSET)
+#define AVR32_HMATRIX_PRAS2 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRAS2_OFFSET)
+#define AVR32_HMATRIX_PRBS2 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRBS2_OFFSET)
+#define AVR32_HMATRIX_PRAS3 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRAS3_OFFSET)
+#define AVR32_HMATRIX_PRBS3 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRBS3_OFFSET)
+#define AVR32_HMATRIX_PRAS4 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRAS4_OFFSET)
+#define AVR32_HMATRIX_PRBS4 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRBS4_OFFSET)
+#define AVR32_HMATRIX_PRAS5 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRAS5_OFFSET)
+#define AVR32_HMATRIX_PRBS5 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRBS5_OFFSET)
+#define AVR32_HMATRIX_PRAS6 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRAS6_OFFSET)
+#define AVR32_HMATRIX_PRBS6 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRBS6_OFFSET)
+#define AVR32_HMATRIX_PRAS7 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRAS7_OFFSET)
+#define AVR32_HMATRIX_PRBS7 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRBS7_OFFSET)
+#define AVR32_HMATRIX_PRAS8 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRAS8_OFFSET)
+#define AVR32_HMATRIX_PRBS8 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRBS8_OFFSET)
+#define AVR32_HMATRIX_PRAS9 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRAS9_OFFSET)
+#define AVR32_HMATRIX_PRBS9 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRBS9_OFFSET)
+#define AVR32_HMATRIX_PRAS10 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRAS10_OFFSET)
+#define AVR32_HMATRIX_PRBS10 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRBS10_OFFSET)
+#define AVR32_HMATRIX_PRAS11 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRAS11_OFFSET)
+#define AVR32_HMATRIX_PRBS11 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRBS11_OFFSET)
+#define AVR32_HMATRIX_PRAS12 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRAS12_OFFSET)
+#define AVR32_HMATRIX_PRBS12 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRBS12_OFFSET)
+#define AVR32_HMATRIX_PRAS13 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRAS13_OFFSET)
+#define AVR32_HMATRIX_PRBS13 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRBS13_OFFSET)
+#define AVR32_HMATRIX_PRAS14 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRAS14_OFFSET)
+#define AVR32_HMATRIX_PRBS14 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRBS14_OFFSET)
+#define AVR32_HMATRIX_PRAS15 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRAS15_OFFSET)
+#define AVR32_HMATRIX_PRBS15 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_PRBS15_OFFSET)
+
+#define AVR32_HMATRIX_SFR(n) (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SFR_OFFSET(n))
+#define AVR32_HMATRIX_SFR0 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SFR0_OFFSET)
+#define AVR32_HMATRIX_SFR1 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SFR1_OFFSET)
+#define AVR32_HMATRIX_SFR2 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SFR2_OFFSET)
+#define AVR32_HMATRIX_SFR3 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SFR3_OFFSET)
+#define AVR32_HMATRIX_SFR4 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SFR4_OFFSET)
+#define AVR32_HMATRIX_SFR5 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SFR5_OFFSET)
+#define AVR32_HMATRIX_SFR6 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SFR6_OFFSET)
+#define AVR32_HMATRIX_SFR7 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SFR7_OFFSET)
+#define AVR32_HMATRIX_SFR8 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SFR8_OFFSET)
+#define AVR32_HMATRIX_SFR9 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SFR9_OFFSET)
+#define AVR32_HMATRIX_SFR10 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SFR10_OFFSET)
+#define AVR32_HMATRIX_SFR11 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SFR11_OFFSET)
+#define AVR32_HMATRIX_SFR12 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SFR12_OFFSET)
+#define AVR32_HMATRIX_SFR13 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SFR13_OFFSET)
+#define AVR32_HMATRIX_SFR14 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SFR14_OFFSET)
+#define AVR32_HMATRIX_SFR15 (AVR32_HMATRIX_BASE+AVR32_HMATRIX_SFR15_OFFSET)
+
+/* Register Bit-field Definitions ***************************************************/
+
+/* Master Configuration Register Bit-field Definitions */
+
+#define HMATRIX_MCFG_UBLT_SHIFT (0) /* Bits 0-2: Undefined Length Burst Type */
+#define HMATRIX_MCFG_UBLT_MASK (7 << HMATRIX_MCFG_UBLT_SHIFT)
+# define HMATRIX_MCFG_UBLT_INF (0 << HMATRIX_MCFG_UBLT_SHIFT) /* Infinite Length Burst */
+# define HMATRIX_MCFG_UBLT_SINGLE (1 << HMATRIX_MCFG_UBLT_SHIFT) /* Single Access */
+# define HMATRIX_MCFG_UBLT_4BEAT (2 << HMATRIX_MCFG_UBLT_SHIFT) /* Four Beat Burst */
+# define HMATRIX_MCFG_UBLT_8BEAT (3 << HMATRIX_MCFG_UBLT_SHIFT) /* Eight Beat Burst */
+# define HMATRIX_MCFG_UBLT_16BEAT (4 << HMATRIX_MCFG_UBLT_SHIFT) /* Sixteen Beat Burst */
+
+/* Slave Configuration Register Bit-field Definitions */
+
+#define HMATRIX_SCFG_SLOTCYCLE_SHIFT (0) /* Bits 0-7: Maximum Number of Allowed Cycles for a Burst
+#define HMATRIX_SCFG_SLOTCYCLE_MASK (0xff << HMATRIX_SCFG_SLOTCYCLE_SHIFT)
+#define HMATRIX_SCFG_DEFMSTRTYPE_SHIFT (16) /* Bits 16-17: Default Master Type
+#define HMATRIX_SCFG_DEFMSTRTYPE_MASK (3 << HMATRIX_SCFG_DEFMSTRTYPE_SHIFT)
+# define HMATRIX_SCFG_DEFMSTRTYPE_NONE (0 << HMATRIX_SCFG_DEFMSTRTYPE_SHIFT)
+# define HMATRIX_SCFG_DEFMSTRTYPE_LAST (1 << HMATRIX_SCFG_DEFMSTRTYPE_SHIFT)
+# define HMATRIX_SCFG_DEFMSTRTYPE_FIXED (2 << HMATRIX_SCFG_DEFMSTRTYPE_SHIFT)
+#define HMATRIX_SCFG_FIXEDDEFMSTR_SHIFT (18) /* Bits 18-21: Fixed Default Master
+#define HMATRIX_SCFG_FIXEDDEFMSTR_MASK (15 << HMATRIX_SCFG_FIXEDDEFMSTR_SHIFT)
+#define HMATRIX_SCFG_ARBT (1 << 24) /* Bit 24: Arbitration Type */
+
+/* Priority Register A for Slave Bit-field Definitions */
+
+#define HMATRIX_PRAS_MPR_SHIFT(n) ((n) << 2)
+#define HMATRIX_PRAS_MPR_MASK(n) (3 << HMATRIX_PRAS_MPR_SHIFT(n))
+#define HMATRIX_PRAS_M0PR_SHIFT (0)
+#define HMATRIX_PRAS_M0PR_MASK (3 << HMATRIX_PRAS_M0PR_SHIFT)
+#define HMATRIX_PRAS_M1PR_SHIFT (4)
+#define HMATRIX_PRAS_M1PR_MASK (3 << HMATRIX_PRAS_M1PR_SHIFT)
+#define HMATRIX_PRAS_M2PR_SHIFT (8)
+#define HMATRIX_PRAS_M2PR_MASK (3 << HMATRIX_PRAS_M2PR_SHIFT)
+#define HMATRIX_PRAS_M3PR_SHIFT (12)
+#define HMATRIX_PRAS_M3PR_MASK (3 << HMATRIX_PRAS_M3PR_SHIFT)
+#define HMATRIX_PRAS_M4PR_SHIFT (16)
+#define HMATRIX_PRAS_M4PR_MASK (3 << HMATRIX_PRAS_M4PR_SHIFT)
+#define HMATRIX_PRAS_M5PR_SHIFT (20)
+#define HMATRIX_PRAS_M5PR_MASK (3 << HMATRIX_PRAS_M5PR_SHIFT)
+#define HMATRIX_PRAS_M6PR_SHIFT (24)
+#define HMATRIX_PRAS_M6PR_MASK (3 << HMATRIX_PRAS_M6PR_SHIFT)
+#define HMATRIX_PRAS_M7PR_SHIFT (28)
+#define HMATRIX_PRAS_M7PR_MASK (3 << HMATRIX_PRAS_M7PR_SHIFT)
+
+/* Priority Register B for Slave Bit-field Definitions */
+
+#define HMATRIX_PRBS_MPR_SHIFT(n) (((n)-8) << 2)
+#define HMATRIX_PRBS_MPR_MASK(n) (3 << HMATRIX_PRBS_MPR_SHIFT(n))
+#define HMATRIX_PRBS_M8PR_SHIFT (0)
+#define HMATRIX_PRBS_M8PR_MASK (3 << HMATRIX_PRBS_M8PR_SHIFT)
+#define HMATRIX_PRBS_M9PR_SHIFT (4)
+#define HMATRIX_PRBS_M9PR_MASK (3 << HMATRIX_PRBS_M9PR_SHIFT)
+#define HMATRIX_PRBS_M10PR_SHIFT (8)
+#define HMATRIX_PRBS_M10PR_MASK (3 << HMATRIX_PRBS_M10PR_SHIFT)
+#define HMATRIX_PRBS_M11PR_SHIFT (12)
+#define HMATRIX_PRBS_M11PR_MASK (3 << HMATRIX_PRBS_M11PR_SHIFT)
+#define HMATRIX_PRBS_M12PR_SHIFT (16)
+#define HMATRIX_PRBS_M12PR_MASK (3 << HMATRIX_PRBS_M12PR_SHIFT)
+#define HMATRIX_PRBS_M13PR_SHIFT (20)
+#define HMATRIX_PRBS_M13PR_MASK (3 << HMATRIX_PRBS_M13PR_SHIFT)
+#define HMATRIX_PRBS_M14PR_SHIFT (24)
+#define HMATRIX_PRBS_M14PR_MASK (3 << HMATRIX_PRBS_M14PR_SHIFT)
+#define HMATRIX_PRBS_M15PR_SHIFT (28)
+#define HMATRIX_PRBS_M15PR_MASK (3 << HMATRIX_PRBS_M15PR_SHIFT)
+
+/* Special Function Register Bit-field Definitions */
+/* This register contains only the 32-bit SFR value and has no bit-fields */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_AVR_SRC_AT32UC3_AT32UC3_HMATRIX_H */
+
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_intc.h b/nuttx/arch/avr/src/at32uc3/at32uc3_intc.h
new file mode 100644
index 000000000..700b27459
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_intc.h
@@ -0,0 +1,98 @@
+/************************************************************************************
+ * arch/avr/src/at32uc3/at32uc3_intc.h
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_AVR_SRC_AT32UC3_AT32UC3_INTC_H
+#define __ARCH_AVR_SRC_AT32UC3_AT32UC3_INTC_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+
+#define AVR32_INTC_IPR_OFFSET(n) ((n) << 2) /* Interrupt priority registers */
+#define AVR32_INTC_IRR_OFFSET(n) (0x100 + ((n) << 2)) /* Interrupt request registers */
+#define AVR32_INTC_ICR_OFFSET(n) (0x20c - ((n) << 2)) /* Interrupt cause registers */
+
+/* Register Addresses ***************************************************************/
+
+#define AVR32_INTC_IPR(n) (AVR32_INTC_BASE+AVR32_INTC_IPR_OFFSET(n))
+#define AVR32_INTC_IRR(n) (AVR32_INTC_BASE+AVR32_INTC_IRR_OFFSET(n))
+#define AVR32_INTC_ICR(n) (AVR32_INTC_BASE+AVR32_INTC_ICR_OFFSET(n))
+
+/* Register Bit-field Definitions ***************************************************/
+
+/* Interrupt priority register bit-field definitions */
+
+#define INTC_IPR_AUTOVECTOR_SHIFT (0) /* Bits 0-13: Autovector address */
+#define INTC_IPR_AUTOVECTOR_MASK (0x3fff << INTC_IPR_AUTOVECTOR_SHIFT)
+#define INTC_IPR_INTLEVEL_SHIFT (30) /* Bits 30-31: Interrupt Level */
+#define INTC_IPR_INTLEVEL_MASK (3 << INTC_IPR_INTLEVEL_SHIFT)
+# define INTC_IPR_INTLEVEL_INT0 (0 << INTC_IPR_INTLEVEL_SHIFT) /* Lowest priority */
+# define INTC_IPR_INTLEVEL_INT1 (1 << INTC_IPR_INTLEVEL_SHIFT)
+# define INTC_IPR_INTLEVEL_INT2 (2 << INTC_IPR_INTLEVEL_SHIFT)
+# define INTC_IPR_INTLEVEL_INT3 (3 << INTC_IPR_INTLEVEL_SHIFT) /* Highest priority */
+
+/* Interrupt request register bit-field definitions */
+
+#define INTC_IRR_REG(n) (AVR32_INTC_IPR((n) >> 5))
+#define INTC_IRR_SHIFT(n) (1 << ((n) & 0x1f))
+#define INTC_IRR_MASK(n) (1 << NTC_IRR_SHIFT(n))
+
+/* Interrupt cause register bit-field definitions */
+
+#define INTC_ICR_CAUSE_SHIFT (0) /* Bits 0-5: Interrupt Group Causing Interrupt of Priority n */
+#define INTC_ICR_CAUSE_MASK (0x3f << INTC_ICR_CAUSE_SHIFT)
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_AVR_SRC_AT32UC3_AT32UC3_INTC_H */
+
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_internal.h b/nuttx/arch/avr/src/at32uc3/at32uc3_internal.h
new file mode 100644
index 000000000..07a2e9136
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_internal.h
@@ -0,0 +1,344 @@
+/****************************************************************************
+ * arch/avr/src/at32uc3b/at32uc3_internal.h
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#ifndef __ARCH_AVR_SRC_AVR32_AT32UC3_INTERNAL_H
+#define __ARCH_AVR_SRC_AVR32_AT32UC3_INTERNAL_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include "at32uc3_config.h"
+
+#ifdef CONFIG_AVR32_GPIOIRQ
+# include <nuttx/irq.h>
+#endif
+
+#include <stdint.h>
+#include <stdbool.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Bit-encoded input to at32uc3_configgpio() ********************************/
+
+/* 16-bit Encoding:
+ * PERIPHERAL: FMMI UXXG PPPB BBBB with G=0
+ * GPIO: FMMI UVOG PPPB BBBB with G=1
+ */
+
+/* Glitch Filter Enable:
+ * F... .... .... ....
+ */
+
+ #define GPIO_GLITCH (1 << 15) /* Bit 15: Glitch filter enable */
+
+/* Interrupt modes (valid only if GPIO_INTR==1)
+ * .MM. .... .... ....
+ */
+
+#define GPIO_INTMODE_SHIFT (13) /* Bits 13-14: Interrupt mode */
+#define GPIO_INTMODE_MASK (3 << GPIO_INTMODE_SHIFT)
+# define GPIO_INTMODE_BOTH (0 << GPIO_INTMODE_SHIFT)
+# define GPIO_INTMODE_RISING (1 << GPIO_INTMODE_SHIFT)
+# define GPIO_INTMODE_FALLING (2 << GPIO_INTMODE_SHIFT)
+
+# define GPIO_IMR0 (1 << GPIO_INTMODE_SHIFT)
+# define GPIO_IMR1 (2 << GPIO_INTMODE_SHIFT)
+
+/* Interrupt enable
+ * ...I .... .... ....
+ */
+
+#define GPIO_INTR (1 << 12) /* Bit 12: Interrupt enable */
+
+/* Pull-up enable
+ * .... U... .... ....
+ */
+
+#define GPIO_PULLUP (1 << 11) /* Bit 11: Pull-up enable */
+
+/* Output value (Valid only if GPIO_ENABLE and GPIO_OUTPUT)
+ * .... .V... .... ....
+ */
+
+#define GPIO_VALUE (1 << 10) /* Bit 10: Output value */
+#define GPIO_HIGH GPIO_VALUE
+#define GPIO_LOW (0)
+
+/* Input/Ouptut (Valid only if GPIO_ENABLE)
+ * .... ..O. .... ....
+ */
+
+#define GPIO_OUTPUT (1 << 9) /* Bit 9: Output driver enable */
+#define GPIO_INPUT (0)
+
+/* Peripheral MUX setting (valid only if GPIO_PERIPH)
+ * .... .XX. .... ....
+ */
+
+#define GPIO_FUNC_SHIFT (9) /* Bits 9-10: Peripheral MUX */
+#define GPIO_FUNC_MASK (3 << GPIO_FUNC_SHIFT)
+# define GPIO_FUNCA (0 << GPIO_FUNC_SHIFT) /* PMR0=0 PMR1=0 */
+# define GPIO_FUNCB (1 << GPIO_FUNC_SHIFT) /* PMR0=1 PMR1=0 */
+# define GPIO_FUNCC (2 << GPIO_FUNC_SHIFT) /* PMR0=0 PMR1=1 */
+# define GPIO_FUNCD (3 << GPIO_FUNC_SHIFT) /* PMR0=1 PMR1=1 */
+
+# define GPIO_PMR0 (1 << GPIO_FUNC_SHIFT)
+# define GPIO_PMR1 (2 << GPIO_FUNC_SHIFT)
+
+/* GPIO Enable (1) or Peripheral Enable (0)
+ * .... .... .... .... .... ...G .... ....
+ */
+
+#define GPIO_ENABLE (1 << 8) /* Bit 8: GPIO enable */
+#define GPIO_PERIPH (0)
+
+
+/* Port Number
+ * .... .... .... .... .... .... PPP. ....
+ */
+
+#define GPIO_PORT_SHIFT (5) /* Bits 5-7: Port number */
+#define GPIO_PORT_MASK (7 << GPIO_PORT_SHIFT)
+# define GPIO_PORTA (0 << GPIO_PORT_SHIFT)
+# define GPIO_PORTB (1 << GPIO_PORT_SHIFT)
+# define GPIO_PORTC (2 << GPIO_PORT_SHIFT)
+# define GPIO_PORTD (3 << GPIO_PORT_SHIFT)
+# define GPIO_PORTE (4 << GPIO_PORT_SHIFT)
+
+/* Pin number:
+ * .... .... .... .... .... .... ...B BBBB
+ */
+
+#define GPIO_PIN_SHIFT (0) /* Bits 0-4: Port number */
+#define GPIO_PIN_MASK (0x1f << GPIO_PIN_SHIFT)
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/****************************************************************************
+ * Inline Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_clkinit
+ *
+ * Description:
+ * Initialiaze clock/PLL settings per the definitions in the board.h file.
+ *
+ ****************************************************************************/
+
+EXTERN void up_clkinitialize(void);
+
+/****************************************************************************
+ * Name: usart_reset
+ *
+ * Description:
+ * Reset a USART.
+ *
+ ****************************************************************************/
+
+EXTERN void usart_reset(uintptr_t usart_base);
+
+/****************************************************************************
+ * Name: usart_configure
+ *
+ * Description:
+ * Configure a USART as a RS-232 UART.
+ *
+ ****************************************************************************/
+
+void usart_configure(uintptr_t usart_base, uint32_t baud, unsigned int parity,
+ unsigned int nbits, bool stop2);
+
+/****************************************************************************
+ * Name: up_consoleinit
+ *
+ * Description:
+ * Initialize a console for debug output. This function is called very
+ * early in the intialization sequence to configure the serial console
+ * uart (only).
+ *
+ ****************************************************************************/
+
+EXTERN void up_consoleinit(void);
+
+/****************************************************************************
+ * Name: up_boardinit
+ *
+ * Description:
+ * This function must be provided by the board-specific logic in the
+ * directory configs/<board-name>/up_boot.c.
+ *
+ ****************************************************************************/
+
+EXTERN void up_boardinitialize(void);
+
+/****************************************************************************
+ * Name: at32uc3_configgpio
+ *
+ * Description:
+ * Configure a GPIO pin based on bit-encoded description of the pin.
+ *
+ ****************************************************************************/
+
+EXTERN int at32uc3_configgpio(uint16_t cfgset);
+
+/****************************************************************************
+ * Name: at32uc3_gpiowrite
+ *
+ * Description:
+ * Write one or zero to the selected GPIO pin
+ *
+ ****************************************************************************/
+
+EXTERN void at32uc3_gpiowrite(uint16_t pinset, bool value);
+
+/****************************************************************************
+ * Name: at32uc3_gpioread
+ *
+ * Description:
+ * Read one or zero from the selected GPIO pin
+ *
+ ****************************************************************************/
+
+EXTERN bool at32uc3_gpioread(uint16_t pinset);
+
+/****************************************************************************
+ * Name: gpio_irqinitialize
+ *
+ * Description:
+ * Initialize all vectors to the unexpected interrupt handler
+ *
+ * Configuration Notes:
+ * Configuration CONFIG_AVR32_GPIOIRQ must be selected to enable the
+ * overall GPIO IRQ feature and CONFIG_AVR32_GPIOIRQSETA and/or
+ * CONFIG_AVR32_GPIOIRQSETB must be enabled to select GPIOs to support
+ * interrupts on.
+ *
+ * Assumptions:
+ * Called during the early boot sequence before global interrupts have
+ * been enabled.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_AVR32_GPIOIRQ
+EXTERN void weak_function gpio_irqinitialize(void);
+#endif
+
+/****************************************************************************
+ * Name: gpio_irqattach
+ *
+ * Description:
+ * Attach in GPIO interrupt to the provide 'isr'
+ *
+ * Configuration Notes:
+ * Configuration CONFIG_AVR32_GPIOIRQ must be selected to enable the
+ * overall GPIO IRQ feature and CONFIG_AVR32_GPIOIRQSETA and/or
+ * CONFIG_AVR32_GPIOIRQSETB must be enabled to select GPIOs to support
+ * interrupts on.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_AVR32_GPIOIRQ
+EXTERN int gpio_irqattach(int irq, xcpt_t newisr, xcpt_t *oldisr);
+#endif
+
+/****************************************************************************
+ * Name: gpio_irqenable
+ *
+ * Description:
+ * Enable the GPIO IRQ specified by 'irq'
+ *
+ * Configuration Notes:
+ * Configuration CONFIG_AVR32_GPIOIRQ must be selected to enable the
+ * overall GPIO IRQ feature and CONFIG_AVR32_GPIOIRQSETA and/or
+ * CONFIG_AVR32_GPIOIRQSETB must be enabled to select GPIOs to support
+ * interrupts on.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_AVR32_GPIOIRQ
+EXTERN void gpio_irqenable(int irq);
+#endif
+
+/*****************************************************************************
+ * Name: gpio_irqdisable
+ *
+ * Description:
+ * Disable the GPIO IRQ specified by 'irq'
+ *
+ * Configuration Notes:
+ * Configuration CONFIG_AVR32_GPIOIRQ must be selected to enable the
+ * overall GPIO IRQ feature and CONFIG_AVR32_GPIOIRQSETA and/or
+ * CONFIG_AVR32_GPIOIRQSETB must be enabled to select GPIOs to support
+ * interrupts on.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_AVR32_GPIOIRQ
+EXTERN void gpio_irqdisable(int irq);
+#endif
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_AVR_SRC_AVR32_AT32UC3_INTERNAL_H */
+
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_irq.c b/nuttx/arch/avr/src/at32uc3/at32uc3_irq.c
new file mode 100644
index 000000000..29fedf057
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_irq.c
@@ -0,0 +1,333 @@
+/****************************************************************************
+ * arch/avr/src/at32uc3_/at32uc3_irq.c
+ * arch/avr/src/chip/at32uc3_irq.c
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include "at32uc3_config.h"
+
+#include <stdint.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+#include <arch/irq.h>
+
+#include "up_arch.h"
+#include "os_internal.h"
+#include "up_internal.h"
+#include "at32uc3_internal.h"
+
+#include "chip.h"
+#include "at32uc3_intc.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* These symbols are exported from up_exceptions.S:
+ */
+
+extern uint32_t vectortab;
+extern uint32_t avr32_int0;
+extern uint32_t avr32_int1;
+extern uint32_t avr32_int2;
+extern uint32_t avr32_int3;
+
+/* The provide interrupt handling offsets relative to the EVBA
+ * address (which should be vectortab).
+ */
+
+#define AVR32_INT0_RADDR ((uint32_t)&avr32_int0 - (uint32_t)&vectortab)
+#define AVR32_INT1_RADDR ((uint32_t)&avr32_int1 - (uint32_t)&vectortab)
+#define AVR32_INT2_RADDR ((uint32_t)&avr32_int2 - (uint32_t)&vectortab)
+#define AVR32_INT3_RADDR ((uint32_t)&avr32_int3 - (uint32_t)&vectortab)
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+uint32_t *current_regs;
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+struct irq_groups_s
+{
+ uint8_t baseirq; /* IRQ number associated with bit 0 */
+ uint8_t nirqs; /* Number of IRQs in this group */
+};
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/* This table maps groups into (1) the base IRQ number for the group and (2)
+ * the number of valid interrupts in the group.
+ */
+
+static const struct irq_groups_s g_grpirqs[AVR32_IRQ_NGROUPS] =
+{
+ {AVR32_IRQ_BASEIRQGRP0, AVR32_IRQ_NREQGRP0 }, /* Group 0 */
+ {AVR32_IRQ_BASEIRQGRP1, AVR32_IRQ_NREQGRP1 }, /* Group 1 */
+ {AVR32_IRQ_BASEIRQGRP2, AVR32_IRQ_NREQGRP2 }, /* Group 2 */
+ {AVR32_IRQ_BASEIRQGRP3, AVR32_IRQ_NREQGRP3 }, /* Group 3 */
+ {AVR32_IRQ_BASEIRQGRP4, AVR32_IRQ_NREQGRP4 }, /* Group 4 */
+ {AVR32_IRQ_BASEIRQGRP5, AVR32_IRQ_NREQGRP5 }, /* Group 5 */
+ {AVR32_IRQ_BASEIRQGRP6, AVR32_IRQ_NREQGRP6 }, /* Group 6 */
+ {AVR32_IRQ_BASEIRQGRP7, AVR32_IRQ_NREQGRP7 }, /* Group 7 */
+ {AVR32_IRQ_BASEIRQGRP8, AVR32_IRQ_NREQGRP8 }, /* Group 8 */
+ {AVR32_IRQ_BASEIRQGRP9, AVR32_IRQ_NREQGRP9 }, /* Group 9 */
+ {AVR32_IRQ_BASEIRQGRP10, AVR32_IRQ_NREQGRP10}, /* Group 10 */
+ {AVR32_IRQ_BASEIRQGRP11, AVR32_IRQ_NREQGRP11}, /* Group 11 */
+ {AVR32_IRQ_BASEIRQGRP12, AVR32_IRQ_NREQGRP12}, /* Group 12 */
+ {AVR32_IRQ_BASEIRQGRP13, AVR32_IRQ_NREQGRP13}, /* Group 13 */
+ {AVR32_IRQ_BASEIRQGRP14, AVR32_IRQ_NREQGRP14}, /* Group 14 */
+ {AVR32_IRQ_BASEIRQGRP15, AVR32_IRQ_NREQGRP15}, /* Group 15 */
+ {AVR32_IRQ_BASEIRQGRP16, AVR32_IRQ_NREQGRP16}, /* Group 16 */
+ {AVR32_IRQ_BASEIRQGRP17, AVR32_IRQ_NREQGRP17}, /* Group 17 */
+ {AVR32_IRQ_BASEIRQGRP18, AVR32_IRQ_NREQGRP18}, /* Group 18 */
+};
+
+/* The following table provides the value of the IPR register to
+ * use to assign a group to different interrupt priorities.
+ */
+
+#if 0 /* REVISIT -- Can we come up with a way to statically initialize? */
+static const uint32_t g_ipr[AVR32_IRQ_INTPRIOS] =
+{
+ ((AVR32_INT0_RADDR << INTC_IPR_INTLEVEL_SHIFT) | INTC_IPR_INTLEVEL_INT0),
+ ((AVR32_INT1_RADDR << INTC_IPR_INTLEVEL_SHIFT) | INTC_IPR_INTLEVEL_INT1),
+ ((AVR32_INT2_RADDR << INTC_IPR_INTLEVEL_SHIFT) | INTC_IPR_INTLEVEL_INT2),
+ ((AVR32_INT3_RADDR << INTC_IPR_INTLEVEL_SHIFT) | INTC_IPR_INTLEVEL_INT3),
+};
+#else
+static uint32_t g_ipr[AVR32_IRQ_INTPRIOS];
+#endif
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_getgrp
+ ****************************************************************************/
+
+static int up_getgrp(unsigned int irq)
+{
+ int i;
+
+ if (irq >= AVR32_IRQ_BASEIRQGRP0)
+ {
+ for (i = 0; i < AVR32_IRQ_NGROUPS; i++)
+ {
+ if (irq < g_grpirqs[i].baseirq + g_grpirqs[i].nirqs)
+ {
+ return i;
+ }
+ }
+ }
+ return -EINVAL;
+}
+
+/****************************************************************************
+ * Name: avr32_xcptn
+ *
+ * Description:
+ * Handlers for unexpected execptions. All are fatal error conditions.
+ *
+ ****************************************************************************/
+
+static int avr32_xcptn(int irq, FAR void *context)
+{
+ (void)irqsave();
+ lldbg("PANIC!!! Exception IRQ: %d\n", irq);
+ PANIC(OSERR_UNEXPECTEDISR);
+ return 0;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_irqinitialize
+ ****************************************************************************/
+
+void up_irqinitialize(void)
+{
+ int group;
+ int irq;
+
+ /* Initialize the table that provides the value of the IPR register to
+ * use to assign a group to different interrupt priorities.
+ */
+
+#if 1 /* REVISIT -- Can we come up with a way to statically initialize? */
+ g_ipr[0] = ((AVR32_INT0_RADDR << INTC_IPR_INTLEVEL_SHIFT) | INTC_IPR_INTLEVEL_INT0);
+ g_ipr[1] = ((AVR32_INT1_RADDR << INTC_IPR_INTLEVEL_SHIFT) | INTC_IPR_INTLEVEL_INT1);
+ g_ipr[2] = ((AVR32_INT2_RADDR << INTC_IPR_INTLEVEL_SHIFT) | INTC_IPR_INTLEVEL_INT2);
+ g_ipr[3] = ((AVR32_INT3_RADDR << INTC_IPR_INTLEVEL_SHIFT) | INTC_IPR_INTLEVEL_INT3);
+#endif
+
+ /* Set the interrupt group priority to a default value. All are linked to
+ * interrupt priority level 0 and to interrupt vector INT0.
+ */
+
+ for (group = 0; group < AVR32_IRQ_MAXGROUPS; group++)
+ {
+ putreg32(g_ipr[0], AVR32_INTC_IPR(group));
+ }
+
+ /* currents_regs is non-NULL only while processing an interrupt */
+
+ current_regs = NULL;
+
+ /* Attach the exception handlers */
+
+ for (irq = 0; irq < AVR32_IRQ_NEVENTS; irq++)
+ {
+ irq_attach(irq, avr32_xcptn);
+ }
+
+ /* Initialize GPIO interrupt facilities */
+
+#ifdef CONFIG_AVR32_GPIOIRQ
+#ifdef CONFIG_HAVE_WEAKFUNCTIONS
+ if (gpio_irqinitialize != NULL)
+#endif
+ {
+ gpio_irqinitialize();
+ }
+#endif
+
+ /* And finally, enable interrupts */
+
+#ifndef CONFIG_SUPPRESS_INTERRUPTS
+ irqrestore(0);
+#endif
+}
+
+/****************************************************************************
+ * Name: up_prioritize_irq
+ *
+ * Description:
+ * Set the priority of an IRQ.
+ *
+ * Since this API is not supported on all architectures, it should be
+ * avoided in common implementations where possible.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_IRQPRIO
+int up_prioritize_irq(int irq, int priority)
+{
+ if (priority >= 0 && priority < AVR32_IRQ_INTPRIOS)
+ {
+ int group = up_getgrp(irq);
+ if (group >= 0)
+ {
+ putreg32(g_ipr[priority], AVR32_INTC_IPR(group));
+ return OK;
+ }
+ }
+ return -EINVAL;
+}
+#endif
+
+/****************************************************************************
+ * Name: avr32_intirqno
+ *
+ * Description:
+ * Return the highest priority pending INTn interrupt (hwere n=level).
+ * This is called directly from interrupt handling logic. This should be
+ * save since the UC3B will save all C scratch/volatile registers (and
+ * this function should not alter the perserved/static registers).
+ *
+ ****************************************************************************/
+
+unsigned int avr32_intirqno(unsigned int level)
+{
+ /* Get the group that caused the interrupt: "ICRn identifies the group with
+ * the highest priority that has a pending interrupt of level n. This value
+ * is only defined when at least one interrupt of level n is pending.
+ */
+
+ uint32_t group = getreg32(AVR32_INTC_ICR(level)) & INTC_ICR_CAUSE_MASK;
+ if (group < AVR32_IRQ_NGROUPS)
+ {
+ /* Now get the set of pending interrupt requests for this group.
+ * Note that we may get spurious interrupts due to races conditions
+ */
+
+ uint32_t irr = getreg32(AVR32_INTC_IRR(group));
+ unsigned irq = g_grpirqs[group].baseirq;
+ uint32_t mask = 1;
+ int i;
+
+ /* Check each interrupt source for this group */
+
+ for (i = 0; i < g_grpirqs[group].nirqs; i++)
+ {
+ /* Is there an interrupt pending? */
+
+ if ((irr & mask) != 0)
+ {
+ /* Yes.. return its IRQ number */
+
+ return irq;
+ }
+
+ /* No.. this is interrupt is not pending */
+
+ irq++;
+ mask <<= 1;
+ }
+
+ lldbg("Spurious interrupt: group=%d IRR=%08x\n", group, irr);
+ return -ENODEV;
+ }
+
+ lldbg("Bad group: %d\n", group);
+ return AVR32_IRQ_BADVECTOR;
+}
+
+
+
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_lowconsole.c b/nuttx/arch/avr/src/at32uc3/at32uc3_lowconsole.c
new file mode 100644
index 000000000..641d7bffe
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_lowconsole.c
@@ -0,0 +1,374 @@
+/******************************************************************************
+ * arch/avr/src/at32uc3/at32uc3_lowconsole.c
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ******************************************************************************/
+
+/******************************************************************************
+ * Included Files
+ ******************************************************************************/
+
+#include <nuttx/config.h>
+#include "at32uc3_config.h"
+
+#include <assert.h>
+#include <debug.h>
+
+#include <arch/irq.h>
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "up_internal.h"
+#include "at32uc3_internal.h"
+#include "at32uc3_usart.h"
+#include "at32uc3_pinmux.h"
+
+/******************************************************************************
+ * Private Definitions
+ ******************************************************************************/
+
+/* Select USART parameters for the selected console */
+
+#if defined(CONFIG_USART0_SERIAL_CONSOLE)
+# define AVR32_CONSOLE_BASE AVR32_USART0_BASE
+# define AVR32_CONSOLE_BAUD CONFIG_USART0_BAUD
+# define AVR32_CONSOLE_BITS CONFIG_USART0_BITS
+# define AVR32_CONSOLE_PARITY CONFIG_USART0_PARITY
+# define AVR32_CONSOLE_2STOP CONFIG_USART0_2STOP
+#elif defined(CONFIG_USART1_SERIAL_CONSOLE)
+# define AVR32_CONSOLE_BASE AVR32_USART1_BASE
+# define AVR32_CONSOLE_BAUD CONFIG_USART1_BAUD
+# define AVR32_CONSOLE_BITS CONFIG_USART1_BITS
+# define AVR32_CONSOLE_PARITY CONFIG_USART1_PARITY
+# define AVR32_CONSOLE_2STOP CONFIG_USART1_2STOP
+#elif defined(CONFIG_USART2_SERIAL_CONSOLE)
+# define AVR32_CONSOLE_BASE AVR32_USART2_BASE
+# define AVR32_CONSOLE_BAUD CONFIG_USART2_BAUD
+# define AVR32_CONSOLE_BITS CONFIG_USART2_BITS
+# define AVR32_CONSOLE_PARITY CONFIG_USART2_PARITY
+# define AVR32_CONSOLE_2STOP CONFIG_USART2_2STOP
+#else
+# error "No CONFIG_USARTn_SERIAL_CONSOLE Setting"
+#endif
+
+/******************************************************************************
+ * Private Types
+ ******************************************************************************/
+
+/******************************************************************************
+ * Private Function Prototypes
+ ******************************************************************************/
+
+/******************************************************************************
+ * Global Variables
+ ******************************************************************************/
+
+/******************************************************************************
+ * Private Variables
+ ******************************************************************************/
+
+/******************************************************************************
+ * Private Functions
+ ******************************************************************************/
+
+/******************************************************************************
+ * Name: usart_putreg
+ *
+ * Description:
+ * Write a value to a USART register
+ *
+ ******************************************************************************/
+
+#ifdef HAVE_RS232_DEVICE
+static inline void usart_putreg(uintptr_t usart_base, unsigned int offset, uint32_t value)
+{
+ putreg32(value, usart_base + offset);
+}
+#endif
+
+/******************************************************************************
+ * Name: usart_getreg
+ *
+ * Description:
+ * Get a value from a USART register
+ *
+ ******************************************************************************/
+
+#ifdef HAVE_RS232_DEVICE
+static inline uint32_t usart_getreg(uintptr_t usart_base, unsigned int offset)
+{
+ return getreg32(usart_base + offset);
+}
+#endif
+
+/******************************************************************************
+ * Name: usart_setbaudrate
+ *
+ * Description:
+ * Configure the UART baud rate.
+ *
+ ******************************************************************************/
+
+#ifdef HAVE_RS232_DEVICE
+static void usart_setbaudrate(uintptr_t usart_base, uint32_t baudrate)
+{
+ uint32_t cd;
+ uint32_t mr;
+
+ /* Select 16x or 8x oversampling mode or go to synchronous mode */
+
+ mr = usart_getreg(usart_base, AVR32_USART_MR_OFFSET);
+ if (baudrate < AVR32_PBA_CLOCK / 16)
+ {
+ /* Select 16x oversampling mode and clear the SYNC mode bit */
+
+ mr &= ~(USART_MR_OVER|USART_MR_SYNC);
+
+ /* Calculate the clock divider assuming 16x oversampling */
+
+ cd = (AVR32_PBA_CLOCK + (baudrate << 3)) / (baudrate << 4);
+ }
+ else if (baudrate < AVR32_PBA_CLOCK / 8)
+ {
+ /* Select 8x oversampling mode and clear the SYNC mode bit */
+
+ mr &= ~USART_MR_SYNC;
+ mr |= USART_MR_OVER;
+
+ /* Calculate the clock divider assuming 16x oversampling */
+
+ cd = (AVR32_PBA_CLOCK + (baudrate << 2)) / (baudrate << 3);
+ }
+ else
+ {
+ /* Set the SYNC mode bit */
+
+ mr |= USART_MR_SYNC;
+
+ /* Use the undivided PBA clock */
+
+ cd = AVR32_PBA_CLOCK / baudrate;
+ }
+
+ DEBUGASSERT(cd > 0 && cd < 65536);
+ usart_putreg(usart_base, AVR32_USART_MR_OFFSET, mr);
+ usart_putreg(usart_base, AVR32_USART_BRGR_OFFSET, cd);
+}
+#endif
+
+/******************************************************************************
+ * Public Functions
+ ******************************************************************************/
+
+/******************************************************************************
+ * Name: usart_reset
+ *
+ * Description:
+ * Reset a USART.
+ *
+ ******************************************************************************/
+
+#ifdef HAVE_RS232_DEVICE
+void usart_reset(uintptr_t usart_base)
+{
+ irqstate_t flags;
+
+ /* Disable all USART interrupts */
+
+ flags = irqsave();
+ usart_putreg(usart_base, AVR32_USART_IDR_OFFSET, 0xffffffff);
+ irqrestore(flags);
+
+ /* Reset mode and other registers */
+
+ usart_putreg(usart_base, AVR32_USART_MR_OFFSET, 0); /* Reset mode register */
+ usart_putreg(usart_base, AVR32_USART_RTOR_OFFSET, 0); /* Reset receiver timeout register */
+ usart_putreg(usart_base, AVR32_USART_TTGR_OFFSET, 0); /* Reset transmitter timeguard reg */
+
+ /* Disable RX and TX, put USART in reset, disable handshaking signals */
+
+ usart_putreg(usart_base, AVR32_USART_CR_OFFSET,
+ USART_CR_RSTRX|USART_CR_RSTTX|USART_CR_RSTSTA|USART_CR_RSTIT|
+ USART_CR_RSTNACK|USART_CR_DTRDIS|USART_CR_RTSDIS);
+}
+#endif
+
+/******************************************************************************
+ * Name: usart_configure
+ *
+ * Description:
+ * Configure a USART as a RS-232 UART.
+ *
+ ******************************************************************************/
+
+#ifdef HAVE_RS232_DEVICE
+void usart_configure(uintptr_t usart_base, uint32_t baud, unsigned int parity,
+ unsigned int nbits, bool stop2)
+{
+ uint32_t regval;
+
+ /* Reset the USART and disable RX and TX */
+
+ usart_reset(usart_base);
+
+ /* Set the baud rate generation register */
+
+ usart_setbaudrate(usart_base, baud);
+
+ /* Configure STOP bits */
+
+ regval = USART_MR_MODE_NORMAL|USART_MR_CHMODE_NORMAL; /* Normal RS-232 mode */
+ regval |= stop2 ? USART_MR_NBSTOP_2 : USART_MR_NBSTOP_1;
+
+ /* Configure parity */
+
+ switch (parity)
+ {
+ case 0:
+ default:
+ regval |= USART_MR_PAR_NONE;
+ break;
+
+ case 1:
+ regval |= USART_MR_PAR_ODD;
+ break;
+
+ case 2:
+ regval |= USART_MR_PAR_EVEN;
+ break;
+ }
+
+ /* Configure the number of bits per word */
+
+ DEBUGASSERT(nbits >= 5 && nbits <= 9);
+ if (nbits == 9)
+ {
+ regval |= USART_MR_MODE9;
+ }
+ else
+ {
+ regval |= USART_MR_CHRL_BITS(nbits);
+ }
+
+ usart_putreg(usart_base, AVR32_USART_MR_OFFSET, regval);
+
+ /* Enable RX and TX */
+
+ regval = usart_getreg(usart_base, AVR32_USART_CR_OFFSET);
+ regval |= (USART_CR_RXEN|USART_CR_TXEN);
+ usart_putreg(usart_base, AVR32_USART_CR_OFFSET, regval);
+}
+#endif
+
+/******************************************************************************
+ * Name: up_consoleinit
+ *
+ * Description:
+ * Initialize a console for debug output. This function is called very
+ * early in the intialization sequence to configure the serial console uart
+ * (only).
+ *
+ ******************************************************************************/
+
+#ifndef CONFIG_USE_EARLYSERIALINIT
+void up_consoleinit(void)
+{
+ /* Enable clocking for the enabled USART modules. Hmmm... It looks like the
+ * default state for CLK_USART0, USART1 CLK_USART1, and USART2 CLK_USART2 is
+ * "enabled" in the PM's PBAMASK register.
+ */
+
+ /* Setup GPIO pins for each configured USART/UART */
+
+#ifdef CONFIG_AVR32_USART0_RS232
+ /* PINMUX_USART0_RXD and PINMUX_USART0_TXD must be defined in board.h. It
+ * must define them be be one of {PINMUX_USART0_RXD_1, PINMUX_USART0_RXD_2}
+ * and {PINMUX_USART_0TXD_1, PINMUX_USART0_TXD_2}, respectively.
+ */
+
+ at32uc3_configgpio(PINMUX_USART0_RXD);
+ at32uc3_configgpio(PINMUX_USART0_TXD);
+
+#endif
+#ifdef CONFIG_AVR32_USART1_RS232
+ /* PINMUX_USART1_RXD and PINMUX_USART1_TXD must be defined in board.h. It
+ * must define them be be one of {PINMUX_USART1_RXD_1, PINMUX_USART1_RXD_2,
+ * PINMUX_USART1_RXD_3} and {PINMUX_USART1_TXD_1, PINMUX_USART1_TXD_2,
+ * PINMUX_USART1_TXD_3}, respectively.
+ */
+
+ at32uc3_configgpio(PINMUX_USART1_RXD);
+ at32uc3_configgpio(PINMUX_USART1_TXD);
+
+#endif
+#ifdef CONFIG_AVR32_USART2_RS232
+ /* PINMUX_USART2_RXD and PINMUX_USART2_TXD must be defined in board.h. It
+ * must define them be be one of {PINMUX_USART2_RXD_1, PINMUX_USART2_RXD_2}
+ * and {PINMUX_USART2_TXD_1, PINMUX_USART2_TXD_2}, respectively.
+ */
+
+ at32uc3_configgpio(PINMUX_USART2_RXD);
+ at32uc3_configgpio(PINMUX_USART2_TXD);
+#endif
+
+ /* Then configure the console here (if it is not going to be configured
+ * by up_earlyserialinit()).
+ */
+
+#if defined(HAVE_SERIAL_CONSOLE) && !defined(CONFIG_USE_EARLYSERIALINIT)
+ usart_configure(AVR32_CONSOLE_BASE, AVR32_CONSOLE_BAUD, AVR32_CONSOLE_PARITY,
+ AVR32_CONSOLE_BITS, (bool)AVR32_CONSOLE_2STOP);
+#endif
+}
+#endif
+
+/******************************************************************************
+ * Name: up_lowputc
+ *
+ * Description:
+ * Output one byte on the serial console
+ *
+ ******************************************************************************/
+
+void up_lowputc(char ch)
+{
+#ifdef HAVE_SERIAL_CONSOLE
+ /* Wait until the TX to become ready */
+
+ while (usart_getreg(AVR32_CONSOLE_BASE, USART_CSR_TXRDY) == 0);
+
+ /* Then send the character */
+
+ usart_putreg(AVR32_CONSOLE_BASE, AVR32_USART_THR_OFFSET, (uint32_t)ch);
+#endif
+}
+
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_lowinit.c b/nuttx/arch/avr/src/at32uc3/at32uc3_lowinit.c
new file mode 100644
index 000000000..d8d62488a
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_lowinit.c
@@ -0,0 +1,107 @@
+/**************************************************************************
+ * arch/avr/src/at32uc3/at32uc3_lowinit.c
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ **************************************************************************/
+
+/**************************************************************************
+ * Included Files
+ **************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "at32uc3_config.h"
+#include "up_internal.h"
+#include "at32uc3_internal.h"
+
+/**************************************************************************
+ * Private Definitions
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Types
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Function Prototypes
+ **************************************************************************/
+
+/**************************************************************************
+ * Global Variables
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Variables
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Functions
+ **************************************************************************/
+
+/**************************************************************************
+ * Public Functions
+ **************************************************************************/
+
+/**************************************************************************
+ * Name: up_lowinit
+ *
+ * Description:
+ * This performs basic initialization of the USART used for the serial
+ * console. Its purpose is to get the console output availabe as soon
+ * as possible.
+ *
+ **************************************************************************/
+
+void up_lowinit(void)
+{
+ /* Initialize MCU clocking */
+
+ up_clkinitialize();
+
+ /* Initialize a console (probably a serial console) */
+
+ up_consoleinit();
+
+ /* Perform early serial initialization (so that we will have debug output
+ * available as soon as possible).
+ */
+
+#ifdef CONFIG_USE_EARLYSERIALINIT
+ up_earlyserialinit();
+#endif
+
+ /* Perform board-level initialization */
+
+ up_boardinitialize();
+}
+
+
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_memorymap.h b/nuttx/arch/avr/src/at32uc3/at32uc3_memorymap.h
new file mode 100644
index 000000000..dfe31ee27
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_memorymap.h
@@ -0,0 +1,114 @@
+/************************************************************************************
+ * arch/avr/src/at32uc3/at32uc3_memorymap.h
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_AVR_SRC_AT32UC3_AT32UC3_MEMORYMAP_H
+#define __ARCH_AVR_SRC_AT32UC3_AT32UC3_MEMORYMAP_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Physical memory map */
+
+#define AVR32_ONCHIP_SRAM_BASE 0x00000000 /* 16-64Kb SRAM */
+#define AVR32_GPIO_LBUS_BASE 0x40000000 /* Local bus mapped GPIO registers */
+#define AVR32_ONCHIP_FLASH_BASE 0x80000000 /* 64-512Kb Flash Array */
+# define AVR32_APPL_BASE 0x80002000 /* 8Kb offset to application w/bootloader */
+# define AVR32_USER_FLASH_BASE 0x80800000 /* Flash User Page */
+# define AVR32_BTLDR_CONFIG 0x808001fc /* Bootloader configuration word */
+#define AVR32_USBDATA_BASE 0xd0000000 /* USB data (64Kb) */
+#define AVR32_HSBPB_BRIDGEB 0xfffe0000 /* HSB-PB Bridge B (64Kb) */
+#define AVR32_HSBPB_BRIDGEA 0xffff0000 /* HSB-PB Bridge A (64Kb) */
+
+/* Memory map for systems without an MMU */
+
+#define AVR32_P1_BASE 0x80000000 /* 512MB non-translated space, cacheable */
+#define AVR32_P2_BASE 0xa0000000 /* 512MB non-translated space, non-cacheable */
+#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_AT32UC3A)
+# define AVR32_VECTOR_BASE AVR32_P1_BASE
+#elif defined(CONFIG_ARCH_CHIP_AT32UC3B)
+# define AVR32_VECTOR_BASE AVR32_P2_BASE
+#else
+# warning "Unknown vector base address"
+#endif
+
+/* Peripheral Address Map */
+
+#define AVR32_USB_BASE 0xfffe0000 /* USB 2.0 Interface */
+#define AVR32_HMATRIX_BASE 0xfffe1000 /* HSB Matrix */
+#define AVR32_HFLASHC_BASE 0xfffe1400 /* Flash Controller */
+#define AVR32_PDCA_BASE 0xffff0000 /* Peripheral DMA Controller */
+#define AVR32_INTC_BASE 0xffff0800 /* Interrupt controller */
+#define AVR32_PM_BASE 0xffff0c00 /* Power Manager */
+#define AVR32_RTC_BASE 0xffff0d00 /* Real Time Counter */
+#define AVR32_WDT_BASE 0xffff0d30 /* Watchdog Timer */
+#define AVR32_EIM_BASE 0xffff0d80 /* External Interrupt Controller */
+#define AVR32_GPIO_BASE 0xffff1000 /* General Purpose Input/Output */
+#define AVR32_USART0_BASE 0xffff1400 /* USART0 */
+#define AVR32_USART1_BASE 0xffff1800 /* USART1 */
+#define AVR32_USART2_BASE 0xffff1c00 /* USART2 */
+#define AVR32_SPI0_BASE 0xffff2400 /* Serial Peripheral Interface 0 */
+#define AVR32_TWI_BASE 0xffff2c00 /* Two-wire Interface */
+#define AVR32_PWM_BASE 0xffff3000 /* Pulse Width Modulation Controller */
+#define AVR32_SSC_BASE 0xffff3400 /* Synchronous Serial Controller */
+#define AVR32_TC_BASE 0xffff3800 /* Timer/Counter */
+#define AVR32_ADC_BASE 0xffff3c00 /* Analog to Digital Converter */
+#define AVR32_ABDAC_BASE 0xffff4000 /* Audio Bitstream DAC */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_AVR_SRC_AT32UC3_AT32UC3_MEMORYMAP_H */
+
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_pdca.h b/nuttx/arch/avr/src/at32uc3/at32uc3_pdca.h
new file mode 100644
index 000000000..7a6c3bfe1
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_pdca.h
@@ -0,0 +1,277 @@
+/************************************************************************************
+ * arch/avr/src/at32uc3/at32uc3_pdca.h
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_AVR_SRC_AT32UC3_AT32UC3_PDCA_H
+#define __ARCH_AVR_SRC_AT32UC3_AT32UC3_PDCA_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+/* DMA Channel Offsets **************************************************************/
+
+#define AVR32_PDCA_CHAN_OFFSET(n) ((n) << 6)
+#define AVR32_PDCA_CHAN0_OFFSET 0x000
+#define AVR32_PDCA_CHAN1_OFFSET 0x040
+#define AVR32_PDCA_CHAN2_OFFSET 0x080
+#define AVR32_PDCA_CHAN3_OFFSET 0x0c0
+#define AVR32_PDCA_CHAN4_OFFSET 0x100
+#define AVR32_PDCA_CHAN5_OFFSET 0x140
+#define AVR32_PDCA_CHAN6_OFFSET 0x180
+#define AVR32_PDCA_CHAN7_OFFSET 0x1c0
+
+/* Channel Register Offsets *********************************************************/
+
+#define AVR32_PDCA_MAR_OFFSET 0x000 /* Memory Address Register */
+#define AVR32_PDCA_PSR_OFFSET 0x004 /* Peripheral Select Register */
+#define AVR32_PDCA_TCR_OFFSET 0x008 /* Transfer Counter Register */
+#define AVR32_PDCA_MARR_OFFSET 0x00C /* Memory Address Reload Register */
+#define AVR32_PDCA_TCRR_OFFSET 0x010 /* Transfer Counter Reload Register */
+#define AVR32_PDCA_CR_OFFSET 0x014 /* Control Register */
+#define AVR32_PDCA_MR_OFFSET 0x018 /* Mode Register */
+#define AVR32_PDCA_SR_OFFSET 0x01C /* Status Register */
+#define AVR32_PDCA_IER_OFFSET 0x020 /* Interrupt Enable Register */
+#define AVR32_PDCA_IDR_OFFSET 0x024 /* Interrupt Disable Register */
+#define AVR32_PDCA_IMR_OFFSET 0x028 /* Interrupt Mask Register */
+#define AVR32_PDCA_ISR_OFFSET 0x02C /* Interrupt Status Register */
+
+/* DMA Channel Base Addresses *******************************************************/
+
+#define AVR32_PDCA_CHAN_BASE(n) (AVR32_PDCA_BASE+AVR32_PDCA_CHAN_OFFSET(n))
+#define AVR32_PDCA_CHAN0_BASE (AVR32_PDCA_BASE+AVR32_PDCA_CHAN0_OFFSET)
+#define AVR32_PDCA_CHAN1_BASE (AVR32_PDCA_BASE+AVR32_PDCA_CHAN1_OFFSET)
+#define AVR32_PDCA_CHAN2_BASE (AVR32_PDCA_BASE+AVR32_PDCA_CHAN2_OFFSET)
+#define AVR32_PDCA_CHAN3_BASE (AVR32_PDCA_BASE+AVR32_PDCA_CHAN3_OFFSET)
+#define AVR32_PDCA_CHAN4_BASE (AVR32_PDCA_BASE+AVR32_PDCA_CHAN4_OFFSET)
+#define AVR32_PDCA_CHAN5_BASE (AVR32_PDCA_BASE+AVR32_PDCA_CHAN5_OFFSET)
+#define AVR32_PDCA_CHAN6_BASE (AVR32_PDCA_BASE+AVR32_PDCA_CHAN6_OFFSET)
+#define AVR32_PDCA_CHAN7_BASE (AVR32_PDCA_BASE+AVR32_PDCA_CHAN7_OFFSET)
+
+/* Channel Register Addresses *******************************************************/
+
+#define AVR32_PDCA_MAR(n) (AVR32_PDCA_CHAN_BASE(n)+AVR32_PDCA_MAR_OFFSET)
+#define AVR32_PDCA_PSR(n) (AVR32_PDCA_CHAN_BASE(n)+AVR32_PDCA_PSR_OFFSET)
+#define AVR32_PDCA_TCR(n) (AVR32_PDCA_CHAN_BASE(n)+AVR32_PDCA_TCR_OFFSET)
+#define AVR32_PDCA_MARR(n) (AVR32_PDCA_CHAN_BASE(n)+AVR32_PDCA_MARR_OFFSET)
+#define AVR32_PDCA_TCRR(n) (AVR32_PDCA_CHAN_BASE(n)+AVR32_PDCA_TCRR_OFFSET)
+#define AVR32_PDCA_CR(n) (AVR32_PDCA_CHAN_BASE(n)+AVR32_PDCA_CR_OFFSET)
+#define AVR32_PDCA_MR(n) (AVR32_PDCA_CHAN_BASE(n)+AVR32_PDCA_MR_OFFSET)
+#define AVR32_PDCA_SR(n) (AVR32_PDCA_CHAN_BASE(n)+AVR32_PDCA_SR_OFFSET)
+#define AVR32_PDCA_IER(n) (AVR32_PDCA_CHAN_BASE(n)+AVR32_PDCA_IER_OFFSET)
+#define AVR32_PDCA_IDR(n) (AVR32_PDCA_CHAN_BASE(n)+AVR32_PDCA_IDR_OFFSET)
+#define AVR32_PDCA_IMR(n) (AVR32_PDCA_CHAN_BASE(n)+AVR32_PDCA_IMR_OFFSET)
+#define AVR32_PDCA_ISR(n) (AVR32_PDCA_CHAN_BASE(n)+AVR32_PDCA_ISR_OFFSET)
+
+#define AVR32_PDCA_CHAN0_MAR (AVR32_PDCA_CHAN0_BASE+AVR32_PDCA_MAR_OFFSET)
+#define AVR32_PDCA_CHAN0_PSR (AVR32_PDCA_CHAN0_BASE+AVR32_PDCA_PSR_OFFSET)
+#define AVR32_PDCA_CHAN0_TCR (AVR32_PDCA_CHAN0_BASE+AVR32_PDCA_TCR_OFFSET)
+#define AVR32_PDCA_CHAN0_MARR (AVR32_PDCA_CHAN0_BASE+AVR32_PDCA_MARR_OFFSET)
+#define AVR32_PDCA_CHAN0_TCRR (AVR32_PDCA_CHAN0_BASE+AVR32_PDCA_TCRR_OFFSET)
+#define AVR32_PDCA_CHAN0_CR (AVR32_PDCA_CHAN0_BASE+AVR32_PDCA_CR_OFFSET)
+#define AVR32_PDCA_CHAN0_MR (AVR32_PDCA_CHAN0_BASE+AVR32_PDCA_MR_OFFSET)
+#define AVR32_PDCA_CHAN0_SR (AVR32_PDCA_CHAN0_BASE+AVR32_PDCA_SR_OFFSET)
+#define AVR32_PDCA_CHAN0_IER (AVR32_PDCA_CHAN0_BASE+AVR32_PDCA_IER_OFFSET)
+#define AVR32_PDCA_CHAN0_IDR (AVR32_PDCA_CHAN0_BASE+AVR32_PDCA_IDR_OFFSET)
+#define AVR32_PDCA_CHAN0_IMR (AVR32_PDCA_CHAN0_BASE+AVR32_PDCA_IMR_OFFSET)
+#define AVR32_PDCA_CHAN0_ISR (AVR32_PDCA_CHAN0_BASE+AVR32_PDCA_ISR_OFFSET)
+
+#define AVR32_PDCA_CHAN1_MAR (AVR32_PDCA_CHAN1_BASE+AVR32_PDCA_MAR_OFFSET)
+#define AVR32_PDCA_CHAN1_PSR (AVR32_PDCA_CHAN1_BASE+AVR32_PDCA_PSR_OFFSET)
+#define AVR32_PDCA_CHAN1_TCR (AVR32_PDCA_CHAN1_BASE+AVR32_PDCA_TCR_OFFSET)
+#define AVR32_PDCA_CHAN1_MARR (AVR32_PDCA_CHAN1_BASE+AVR32_PDCA_MARR_OFFSET)
+#define AVR32_PDCA_CHAN1_TCRR (AVR32_PDCA_CHAN1_BASE+AVR32_PDCA_TCRR_OFFSET)
+#define AVR32_PDCA_CHAN1_CR (AVR32_PDCA_CHAN1_BASE+AVR32_PDCA_CR_OFFSET)
+#define AVR32_PDCA_CHAN1_MR (AVR32_PDCA_CHAN1_BASE+AVR32_PDCA_MR_OFFSET)
+#define AVR32_PDCA_CHAN1_SR (AVR32_PDCA_CHAN1_BASE+AVR32_PDCA_SR_OFFSET)
+#define AVR32_PDCA_CHAN1_IER (AVR32_PDCA_CHAN1_BASE+AVR32_PDCA_IER_OFFSET)
+#define AVR32_PDCA_CHAN1_IDR (AVR32_PDCA_CHAN1_BASE+AVR32_PDCA_IDR_OFFSET)
+#define AVR32_PDCA_CHAN1_IMR (AVR32_PDCA_CHAN1_BASE+AVR32_PDCA_IMR_OFFSET)
+#define AVR32_PDCA_CHAN1_ISR (AVR32_PDCA_CHAN1_BASE+AVR32_PDCA_ISR_OFFSET)
+
+#define AVR32_PDCA_CHAN2_MAR (AVR32_PDCA_CHAN2_BASE+AVR32_PDCA_MAR_OFFSET)
+#define AVR32_PDCA_CHAN2_PSR (AVR32_PDCA_CHAN2_BASE+AVR32_PDCA_PSR_OFFSET)
+#define AVR32_PDCA_CHAN2_TCR (AVR32_PDCA_CHAN2_BASE+AVR32_PDCA_TCR_OFFSET)
+#define AVR32_PDCA_CHAN2_MARR (AVR32_PDCA_CHAN2_BASE+AVR32_PDCA_MARR_OFFSET)
+#define AVR32_PDCA_CHAN2_TCRR (AVR32_PDCA_CHAN2_BASE+AVR32_PDCA_TCRR_OFFSET)
+#define AVR32_PDCA_CHAN2_CR (AVR32_PDCA_CHAN2_BASE+AVR32_PDCA_CR_OFFSET)
+#define AVR32_PDCA_CHAN2_MR (AVR32_PDCA_CHAN2_BASE+AVR32_PDCA_MR_OFFSET)
+#define AVR32_PDCA_CHAN2_SR (AVR32_PDCA_CHAN2_BASE+AVR32_PDCA_SR_OFFSET)
+#define AVR32_PDCA_CHAN2_IER (AVR32_PDCA_CHAN2_BASE+AVR32_PDCA_IER_OFFSET)
+#define AVR32_PDCA_CHAN2_IDR (AVR32_PDCA_CHAN2_BASE+AVR32_PDCA_IDR_OFFSET)
+#define AVR32_PDCA_CHAN2_IMR (AVR32_PDCA_CHAN2_BASE+AVR32_PDCA_IMR_OFFSET)
+#define AVR32_PDCA_CHAN2_ISR (AVR32_PDCA_CHAN2_BASE+AVR32_PDCA_ISR_OFFSET)
+
+#define AVR32_PDCA_CHAN3_MAR (AVR32_PDCA_CHAN3_BASE+AVR32_PDCA_MAR_OFFSET)
+#define AVR32_PDCA_CHAN3_PSR (AVR32_PDCA_CHAN3_BASE+AVR32_PDCA_PSR_OFFSET)
+#define AVR32_PDCA_CHAN3_TCR (AVR32_PDCA_CHAN3_BASE+AVR32_PDCA_TCR_OFFSET)
+#define AVR32_PDCA_CHAN3_MARR (AVR32_PDCA_CHAN3_BASE+AVR32_PDCA_MARR_OFFSET)
+#define AVR32_PDCA_CHAN3_TCRR (AVR32_PDCA_CHAN3_BASE+AVR32_PDCA_TCRR_OFFSET)
+#define AVR32_PDCA_CHAN3_CR (AVR32_PDCA_CHAN3_BASE+AVR32_PDCA_CR_OFFSET)
+#define AVR32_PDCA_CHAN3_MR (AVR32_PDCA_CHAN3_BASE+AVR32_PDCA_MR_OFFSET)
+#define AVR32_PDCA_CHAN3_SR (AVR32_PDCA_CHAN3_BASE+AVR32_PDCA_SR_OFFSET)
+#define AVR32_PDCA_CHAN3_IER (AVR32_PDCA_CHAN3_BASE+AVR32_PDCA_IER_OFFSET)
+#define AVR32_PDCA_CHAN3_IDR (AVR32_PDCA_CHAN3_BASE+AVR32_PDCA_IDR_OFFSET)
+#define AVR32_PDCA_CHAN3_IMR (AVR32_PDCA_CHAN3_BASE+AVR32_PDCA_IMR_OFFSET)
+#define AVR32_PDCA_CHAN3_ISR (AVR32_PDCA_CHAN3_BASE+AVR32_PDCA_ISR_OFFSET)
+
+#define AVR32_PDCA_CHAN4_MAR (AVR32_PDCA_CHAN4_BASE+AVR32_PDCA_MAR_OFFSET)
+#define AVR32_PDCA_CHAN4_PSR (AVR32_PDCA_CHAN4_BASE+AVR32_PDCA_PSR_OFFSET)
+#define AVR32_PDCA_CHAN4_TCR (AVR32_PDCA_CHAN4_BASE+AVR32_PDCA_TCR_OFFSET)
+#define AVR32_PDCA_CHAN4_MARR (AVR32_PDCA_CHAN4_BASE+AVR32_PDCA_MARR_OFFSET)
+#define AVR32_PDCA_CHAN4_TCRR (AVR32_PDCA_CHAN4_BASE+AVR32_PDCA_TCRR_OFFSET)
+#define AVR32_PDCA_CHAN4_CR (AVR32_PDCA_CHAN4_BASE+AVR32_PDCA_CR_OFFSET)
+#define AVR32_PDCA_CHAN4_MR (AVR32_PDCA_CHAN4_BASE+AVR32_PDCA_MR_OFFSET)
+#define AVR32_PDCA_CHAN4_SR (AVR32_PDCA_CHAN4_BASE+AVR32_PDCA_SR_OFFSET)
+#define AVR32_PDCA_CHAN4_IER (AVR32_PDCA_CHAN4_BASE+AVR32_PDCA_IER_OFFSET)
+#define AVR32_PDCA_CHAN4_IDR (AVR32_PDCA_CHAN4_BASE+AVR32_PDCA_IDR_OFFSET)
+#define AVR32_PDCA_CHAN4_IMR (AVR32_PDCA_CHAN4_BASE+AVR32_PDCA_IMR_OFFSET)
+#define AVR32_PDCA_CHAN4_ISR (AVR32_PDCA_CHAN4_BASE+AVR32_PDCA_ISR_OFFSET)
+
+#define AVR32_PDCA_CHAN5_MAR (AVR32_PDCA_CHAN5_BASE+AVR32_PDCA_MAR_OFFSET)
+#define AVR32_PDCA_CHAN5_PSR (AVR32_PDCA_CHAN5_BASE+AVR32_PDCA_PSR_OFFSET)
+#define AVR32_PDCA_CHAN5_TCR (AVR32_PDCA_CHAN5_BASE+AVR32_PDCA_TCR_OFFSET)
+#define AVR32_PDCA_CHAN5_MARR (AVR32_PDCA_CHAN5_BASE+AVR32_PDCA_MARR_OFFSET)
+#define AVR32_PDCA_CHAN5_TCRR (AVR32_PDCA_CHAN5_BASE+AVR32_PDCA_TCRR_OFFSET)
+#define AVR32_PDCA_CHAN5_CR (AVR32_PDCA_CHAN5_BASE+AVR32_PDCA_CR_OFFSET)
+#define AVR32_PDCA_CHAN5_MR (AVR32_PDCA_CHAN5_BASE+AVR32_PDCA_MR_OFFSET)
+#define AVR32_PDCA_CHAN5_SR (AVR32_PDCA_CHAN5_BASE+AVR32_PDCA_SR_OFFSET)
+#define AVR32_PDCA_CHAN5_IER (AVR32_PDCA_CHAN5_BASE+AVR32_PDCA_IER_OFFSET)
+#define AVR32_PDCA_CHAN5_IDR (AVR32_PDCA_CHAN5_BASE+AVR32_PDCA_IDR_OFFSET)
+#define AVR32_PDCA_CHAN5_IMR (AVR32_PDCA_CHAN5_BASE+AVR32_PDCA_IMR_OFFSET)
+#define AVR32_PDCA_CHAN5_ISR (AVR32_PDCA_CHAN5_BASE+AVR32_PDCA_ISR_OFFSET)
+
+#define AVR32_PDCA_CHAN6_MAR (AVR32_PDCA_CHAN6_BASE+AVR32_PDCA_MAR_OFFSET)
+#define AVR32_PDCA_CHAN6_PSR (AVR32_PDCA_CHAN6_BASE+AVR32_PDCA_PSR_OFFSET)
+#define AVR32_PDCA_CHAN6_TCR (AVR32_PDCA_CHAN6_BASE+AVR32_PDCA_TCR_OFFSET)
+#define AVR32_PDCA_CHAN6_MARR (AVR32_PDCA_CHAN6_BASE+AVR32_PDCA_MARR_OFFSET)
+#define AVR32_PDCA_CHAN6_TCRR (AVR32_PDCA_CHAN6_BASE+AVR32_PDCA_TCRR_OFFSET)
+#define AVR32_PDCA_CHAN6_CR (AVR32_PDCA_CHAN6_BASE+AVR32_PDCA_CR_OFFSET)
+#define AVR32_PDCA_CHAN6_MR (AVR32_PDCA_CHAN6_BASE+AVR32_PDCA_MR_OFFSET)
+#define AVR32_PDCA_CHAN6_SR (AVR32_PDCA_CHAN6_BASE+AVR32_PDCA_SR_OFFSET)
+#define AVR32_PDCA_CHAN6_IER (AVR32_PDCA_CHAN6_BASE+AVR32_PDCA_IER_OFFSET)
+#define AVR32_PDCA_CHAN6_IDR (AVR32_PDCA_CHAN6_BASE+AVR32_PDCA_IDR_OFFSET)
+#define AVR32_PDCA_CHAN6_IMR (AVR32_PDCA_CHAN6_BASE+AVR32_PDCA_IMR_OFFSET)
+#define AVR32_PDCA_CHAN6_ISR (AVR32_PDCA_CHAN6_BASE+AVR32_PDCA_ISR_OFFSET)
+
+#define AVR32_PDCA_CHAN7_MAR (AVR32_PDCA_CHAN7_BASE+AVR32_PDCA_MAR_OFFSET)
+#define AVR32_PDCA_CHAN7_PSR (AVR32_PDCA_CHAN7_BASE+AVR32_PDCA_PSR_OFFSET)
+#define AVR32_PDCA_CHAN7_TCR (AVR32_PDCA_CHAN7_BASE+AVR32_PDCA_TCR_OFFSET)
+#define AVR32_PDCA_CHAN7_MARR (AVR32_PDCA_CHAN7_BASE+AVR32_PDCA_MARR_OFFSET)
+#define AVR32_PDCA_CHAN7_TCRR (AVR32_PDCA_CHAN7_BASE+AVR32_PDCA_TCRR_OFFSET)
+#define AVR32_PDCA_CHAN7_CR (AVR32_PDCA_CHAN7_BASE+AVR32_PDCA_CR_OFFSET)
+#define AVR32_PDCA_CHAN7_MR (AVR32_PDCA_CHAN7_BASE+AVR32_PDCA_MR_OFFSET)
+#define AVR32_PDCA_CHAN7_SR (AVR32_PDCA_CHAN7_BASE+AVR32_PDCA_SR_OFFSET)
+#define AVR32_PDCA_CHAN7_IER (AVR32_PDCA_CHAN7_BASE+AVR32_PDCA_IER_OFFSET)
+#define AVR32_PDCA_CHAN7_IDR (AVR32_PDCA_CHAN7_BASE+AVR32_PDCA_IDR_OFFSET)
+#define AVR32_PDCA_CHAN7_IMR (AVR32_PDCA_CHAN7_BASE+AVR32_PDCA_IMR_OFFSET)
+#define AVR32_PDCA_CHAN7_ISR (AVR32_PDCA_CHAN7_BASE+AVR32_PDCA_ISR_OFFSET)
+
+/* Channel Register Bit-field Definitions *******************************************/
+
+/* Memory Address Register Bit-field Definitions */
+/* Memory Address Reload Register Bit-field Definitions */
+/* These registers hold a 32-bit address and contain no bit-fields */
+
+/* Peripheral Select Register Bit-field Definitions */
+
+#define PDCA_PSR_PID_SHIFT (0) /* Bits 0-7: Peripheral Identifier */
+#define PDCA_PSR_PID_MASK (0xff << PDCA_PSR_PID_SHIFT)
+# define PDCA_PSR_PID_ADC (0 << PDCA_PSR_PID_SHIFT) /* ADC */
+# define PDCA_PSR_PID_SSCRX (1 << PDCA_PSR_PID_SHIFT) /* SSC - RX */
+# define PDCA_PSR_PID_USART0RX (2 << PDCA_PSR_PID_SHIFT) /* USART0 - RX */
+# define PDCA_PSR_PID_USART1RX (3 << PDCA_PSR_PID_SHIFT) /* USART1 - RX */
+# define PDCA_PSR_PID_USART2RX (4 << PDCA_PSR_PID_SHIFT) /* USART2 - RX */
+# define PDCA_PSR_PID_TWIRX (5 << PDCA_PSR_PID_SHIFT) /* TWI - RX */
+# define PDCA_PSR_PID_SPI0RX (6 << PDCA_PSR_PID_SHIFT) /* SPI0 - RX */
+# define PDCA_PSR_PID_SSCTX (7 << PDCA_PSR_PID_SHIFT) /* SSC - TX */
+# define PDCA_PSR_PID_USART0TX (8 << PDCA_PSR_PID_SHIFT) /* USART0 - TX */
+# define PDCA_PSR_PID_USART1TX (9 << PDCA_PSR_PID_SHIFT) /* USART1 - TX */
+# define PDCA_PSR_PID_USART2TX (10 << PDCA_PSR_PID_SHIFT) /* USART2 - TX */
+# define PDCA_PSR_PID_TWITX (11 << PDCA_PSR_PID_SHIFT) /* TWI - TX */
+# define PDCA_PSR_PID_SPI0TX (12 << PDCA_PSR_PID_SHIFT) /* SPI0 - TX */
+# define PDCA_PSR_PID_ABDACTX (13 << PDCA_PSR_PID_SHIFT) /* ABDAC - TX */
+
+/* Transfer Counter Register Bit-field Definitions */
+/* Transfer Counter Reload Register Bit-field Definitions */
+
+#define PDCA_TCV_SHIFT (0) /* Bits 0-15: Transfer Counter Value */
+#define PDCA_TCV_MASK (0xffff << PDCA_TCV_SHIFT)
+
+/* Control Register Bit-field Definitions */
+
+#define PDCA_CR_TEN (1 << 0) /* Bit 0: Transfer Enable */
+#define PDCA_CR_TDIS (1 << 1) /* Bit 1: Transfer Disable */
+#define PDCA_CR_ECLR (1 << 8) /* Bit 8: Transfer Error Clear */
+
+/* Mode Register Bit-field Definitions */
+
+#define PDCA_MR_SIZE_SHIFT (0) /* Bits 0-1: Prescale Select */
+#define PDCA_MR_SIZE_MASK (3 << PDCA_MR_SIZE_SHIFT)
+# define PDCA_MR_SIZE_ BYTE (0 << PDCA_MR_SIZE_SHIFT) /* Byte */
+# define PDCA_MR_SIZE_ HWORD (1 << PDCA_MR_SIZE_SHIFT) /* Halfword */
+# define PDCA_MR_SIZE_ WORD (2 << PDCA_MR_SIZE_SHIFT) /* Word */
+
+/* Status Register Bit-field Definitions */
+
+#define PDCA_SR_TEN (1 << 0) /* Bit 0: Transfer Enabled */
+
+/* Interrupt Enable Register Bit-field Definitions */
+/* Interrupt Disable Register Bit-field Definitions */
+/* Interrupt Mask Register Bit-field Definitions */
+/* Interrupt Status Register Bit-field Definitions */
+
+#define PDCA_INT_RCZ (1 << 0) /* Bit 0: Reload Counter Zero */
+#define PDCA_INT_TRC (1 << 1) /* Bit 1: Transfer Complete */
+#define PDCA_INT_TERR (1 << 2) /* Bit 2: Transfer Error */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_AVR_SRC_AT32UC3_AT32UC3_PDCA_H */
+
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_pinmux.h b/nuttx/arch/avr/src/at32uc3/at32uc3_pinmux.h
new file mode 100644
index 000000000..0c55fb94c
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_pinmux.h
@@ -0,0 +1,71 @@
+/************************************************************************************
+ * arch/avr/src/at32uc3/at32uc3_pinmux.h
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_AVR_SRC_AT32UC3_AT32UC3_PINMUX_H
+#define __ARCH_AVR_SRC_AT32UC3_AT32UC3_PINMUX_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include "chip.h"
+
+#if defined(CONFIG_ARCH_CHIP_AT32UC3B)
+# include "at32uc3b_pinmux.h"
+#elif defined(CONFIG_ARCH_CHIP_AT32UC3A)
+# include "at32uc3a_pinmux.h"
+#else
+# error "Unknown AVR32 chip"
+#endif
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_AVR_SRC_AT32UC3_AT32UC3_PINMUX_H */
+
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_pm.h b/nuttx/arch/avr/src/at32uc3/at32uc3_pm.h
new file mode 100644
index 000000000..786cf1d68
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_pm.h
@@ -0,0 +1,335 @@
+/************************************************************************************
+ * arch/avr/src/at32uc3/at32uc3_pm.h
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_AVR_SRC_AT32UC3_AT32UC3_PM_H
+#define __ARCH_AVR_SRC_AT32UC3_AT32UC3_PM_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+
+#define AVR32_PM_MCCTRL_OFFSET 0x0000 /* Main Clock Control Register */
+#define AVR32_PM_CKSEL_OFFSET 0x0004 /* Clock Select Register */
+#define AVR32_PM_CPUMASK_OFFSET 0x0008 /* CPU Mask Register */
+#define AVR32_PM_HSBMASK_OFFSET 0x000c /* HSB Mask Register */
+#define AVR32_PM_PBAMASK_OFFSET 0x0010 /* PBA Mask Register */
+#define AVR32_PM_PBBMASK_OFFSET 0x0014 /* PBB Mask Register */
+#define AVR32_PM_PLL0_OFFSET 0x0020 /* PLL0 Control Register */
+#define AVR32_PM_PLL1_OFFSET 0x0024 /* PLL1 Control Register */
+#define AVR32_PM_OSCCTRL0_OFFSET 0x0028 /* Oscillator 0 Control Register */
+#define AVR32_PM_OSCCTRL1_OFFSET 0x002c /* Oscillator 1 Control Register */
+#define AVR32_PM_OSCCTRL32_OFFSET 0x0030 /* Oscillator 32 Control Register */
+#define AVR32_PM_IER_OFFSET 0x0040 /* Interrupt Enable Register */
+#define AVR32_PM_IDR_OFFSET 0x0044 /* Interrupt Disable Register */
+#define AVR32_PM_IMR_OFFSET 0x0048 /* Interrupt Mask Register */
+#define AVR32_PM_ISR_OFFSET 0x004c /* Interrupt Status Register */
+#define AVR32_PM_ICR_OFFSET 0x0050 /* Interrupt Clear Register */
+#define AVR32_PM_POSCSR_OFFSET 0x0054 /* Power and Oscillators Status Register */
+#define AVR32_PM_GCCTRL_OFFSET(n) (0x0060+((n)<<2)) /* 0x0060-0x070 Generic Clock Control Register */
+#define AVR32_PM_RCCR_OFFSET 0x00c0 /* RC Oscillator Calibration Register */
+#define AVR32_PM_BGCR_OFFSET 0x00c4 /* Bandgap Calibration Register */
+#define AVR32_PM_VREGCR_OFFSET 0x00c8 /* Linear Regulator Calibration Register */
+#define AVR32_PM_BOD_OFFSET 0x00d0 /* BOD Level Register BOD Read/Write */
+#define AVR32_PM_RCAUSE_OFFSET 0x0140 /* Reset Cause Register */
+#define AVR32_PM_AWEN_OFFSET 0x0144 /* Asynchronous Wake Up Enable Register */
+#define AVR32_PM_GPLP0_OFFSET 0x0200 /* General Purpose Low-Power Register 0 */
+#define AVR32_PM_GPLP1_OFFSET 0x0204 /* General Purpose Low-Power Register 1 */
+
+/* Register Addresses ***************************************************************/
+
+#define AVR32_PM_MCCTRL (AVR32_PM_BASE+AVR32_PM_MCCTRL_OFFSET)
+#define AVR32_PM_CKSEL (AVR32_PM_BASE+AVR32_PM_CKSEL_OFFSET)
+#define AVR32_PM_CPUMASK (AVR32_PM_BASE+AVR32_PM_CPUMASK_OFFSET)
+#define AVR32_PM_HSBMASK (AVR32_PM_BASE+AVR32_PM_HSBMASK_OFFSET)
+#define AVR32_PM_PBAMASK (AVR32_PM_BASE+AVR32_PM_PBAMASK_OFFSET)
+#define AVR32_PM_PBBMASK (AVR32_PM_BASE+AVR32_PM_PBBMASK_OFFSET)
+#define AVR32_PM_PLL0 (AVR32_PM_BASE+AVR32_PM_PLL0_OFFSET)
+#define AVR32_PM_PLL1 (AVR32_PM_BASE+AVR32_PM_PLL1_OFFSET)
+#define AVR32_PM_OSCCTRL0 (AVR32_PM_BASE+AVR32_PM_OSCCTRL0_OFFSET)
+#define AVR32_PM_OSCCTRL1 (AVR32_PM_BASE+AVR32_PM_OSCCTRL1_OFFSET)
+#define AVR32_PM_OSCCTRL32 (AVR32_PM_BASE+AVR32_PM_OSCCTRL32_OFFSET)
+#define AVR32_PM_IER (AVR32_PM_BASE+AVR32_PM_IER_OFFSET)
+#define AVR32_PM_IDR (AVR32_PM_BASE+AVR32_PM_IDR_OFFSET)
+#define AVR32_PM_IMR (AVR32_PM_BASE+AVR32_PM_IMR_OFFSET)
+#define AVR32_PM_ISR (AVR32_PM_BASE+AVR32_PM_ISR_OFFSET)
+#define AVR32_PM_ICR (AVR32_PM_BASE+AVR32_PM_ICR_OFFSET)
+#define AVR32_PM_POSCSR (AVR32_PM_BASE+AVR32_PM_POSCSR_OFFSET)
+#define AVR32_PM_GCCTRL(n) (AVR32_PM_BASE+AVR32_PM_GCCTRL_OFFSET(n))
+#define AVR32_PM_RCCR (AVR32_PM_BASE+AVR32_PM_RCCR_OFFSET)
+#define AVR32_PM_BGCR (AVR32_PM_BASE+AVR32_PM_BGCR_OFFSET)
+#define AVR32_PM_VREGCR (AVR32_PM_BASE+AVR32_PM_VREGCR_OFFSET)
+#define AVR32_PM_BOD (AVR32_PM_BASE+AVR32_PM_BOD_OFFSET)
+#define AVR32_PM_RCAUSE (AVR32_PM_BASE+AVR32_PM_RCAUSE_OFFSET)
+#define AVR32_PM_AWEN (AVR32_PM_BASE+AVR32_PM_AWEN_OFFSET)
+#define AVR32_PM_GPLP0 (AVR32_PM_BASE+AVR32_PM_GPLP0_OFFSET)
+#define AVR32_PM_GPLP1 (AVR32_PM_BASE+AVR32_PM_GPLP1_OFFSET)
+
+/* Register Bit-field Definitions ***************************************************/
+
+/* Main Clock Control Register Bit-field Definitions */
+
+#define PM_MCCTRL_MCSEL_SHIFT (0) /* Bits 0-1: Main Clock Select */
+#define PM_MCCTRL_MCSEL_MASK (3 << PM_MCCTRL_MCSEL_SHIFT)
+# define PM_MCCTRL_MCSEL_SLOW (0 << PM_MCCTRL_MCSEL_SHIFT) /* slow clock is source */
+# define PM_MCCTRL_MCSEL_OSC0 (1 << PM_MCCTRL_MCSEL_SHIFT) /* Oscillator 0 is source */
+# define PM_MCCTRL_MCSEL_PLL0 (2 << PM_MCCTRL_MCSEL_SHIFT) /* PLL0 is source */
+#define PM_MCCTRL_OSC0EN (1 << 2) /* Bit 2: Oscillator 0 Enable */
+#define PM_MCCTRL_OSC1EN (1 << 3) /* Bit 3: Oscillator 1 Enable */
+
+/* Clock Select Register Bit-field Definitions */
+
+#define PM_CKSEL_CPUSEL_SHIFT (0) /* Bits 0-2: CPU Clock Select */
+#define PM_CKSEL_CPUSEL_MASK (7 << PM_CKSEL_CPUSEL_SHIFT)
+#define PM_CKSEL_CPUDIV (1 << 7) /* Bit 7: CPU Division */
+#define PM_CKSEL_HSBSEL_SHIFT (8) /* Bits 8-10: HSB Clock Select */
+#define PM_CKSEL_HSBSEL_MASK (7 << PM_CKSEL_HSBSEL_SHIFT)
+#define PM_CKSEL_HSBDIV (1 << 15) /* Bit 15: HSB Division */
+#define PM_CKSEL_PBASEL_SHIFT (16) /* Bits 16-28: BA Clock Select */
+#define PM_CKSEL_PBASEL_MASK (7 << PM_CKSEL_PBASEL_SHIFT)
+#define PM_CKSEL_PBADIV (1 << 23) /* Bit 23: PBA Division */
+#define PM_CKSEL_PBBSEL_SHIFT (24) /* Bits 24-26: PBB Clock Select */
+#define PM_CKSEL_PBBSEL_MASK (7 << PM_CKSEL_PBBSEL_SHIFT)
+#define PM_CKSEL_PBBDIV (1 << 31) /* Bit 31: PBB Division */
+
+/* CPU Mask Register Bit-field Definitions */
+
+#define PM_CPUMASK_OCD (1 << 1) /* Bit 1: OCD */
+
+/* HSB Mask Register Bit-field Definitions */
+
+#define PM_HSBMASK_FLASHC (1 << 0) /* Bit 0: FLASHC */
+#define PM_HSBMASK_PBA (1 << 1) /* Bit 1: PBA bridge */
+#define PM_HSBMASK_PBB (1 << 2) /* Bit 2: PBB bridge */
+#define PM_HSBMASK_USBB (1 << 3) /* Bit 3: USBB */
+#define PM_HSBMASK_PDCA (1 << 4) /* Bit 4: PDCA */
+
+/* PBA Mask Register Bit-field Definitions */
+
+#define PM_PBAMASK_INTC (1 << 0) /* Bit 0: INTC */
+#define PM_PBAMASK_GPIO (1 << 1) /* Bit 1: GPIO */
+#define PM_PBAMASK_PDCA (1 << 2) /* Bit 2: PDCA */
+#define PM_PBAMASK_PMRTCEIC (1 << 3) /* Bit 3: PM/RTC/EIC */
+#define PM_PBAMASK_ADC (1 << 4) /* Bit 4: ADC */
+#define PM_PBAMASK_SPI (1 << 5) /* Bit 5: SPI */
+#define PM_PBAMASK_TWI (1 << 6) /* Bit 6: TWI */
+#define PM_PBAMASK_USART0 (1 << 7) /* Bit 7: USART0 */
+#define PM_PBAMASK_USART1 (1 << 8) /* Bit 8: USART1 */
+#define PM_PBAMASK_USART2 (1 << 9) /* Bit 9: USART2 */
+#define PM_PBAMASK_PWM (1 << 10) /* Bit 10: PWM */
+#define PM_PBAMASK_SSC (1 << 11) /* Bit 11: SSC */
+#define PM_PBAMASK_TC (1 << 12) /* Bit 12: TC */
+#define PM_PBAMASK_ABDAC (1 << 13) /* Bit 13: ABDAC */
+
+/* PBB Mask Register Bit-field Definitions */
+
+#define PM_PBBMASK_HMATRIX (1 << 0) /* Bit 0: HMATRIX */
+#define PM_PBBMASK_USBB (1 << 2) /* Bit 2: USBB */
+#define PM_PBBMASK_FLASHC (1 << 3) /* Bit 3: FLASHC */
+
+/* PLL0/1 Control Register Bit-field Definitions */
+
+#define PM_PLL_PLLEN (1 << 0) /* Bit 0: PLL Enable */
+#define PM_PLL_PLLOSC (1 << 1) /* Bit 1: PLL Oscillator Select */
+#define PM_PLL_PLLOPT_SHIFT (2) /* Bits 2-3: PLL Option */
+#define PM_PLL_PLLOPT_MASK (7 << PM_PLL_PLLOPT_SHIFT)
+# define PM_PLL_PLLOPT_VCO (1 << PM_PLL_PLLOPT_SHIFT) /* Select the VCO frequency range */
+# define PM_PLL_PLLOPT_XTRADIV (2 << PM_PLL_PLLOPT_SHIFT) /* Enable the extra output divider */
+# define PM_PLL_PLLOPT_WBWDIS (4 << PM_PLL_PLLOPT_SHIFT) /* Disable the Wide-Bandwidth mode */
+#define PM_PLL_PLLDIV_SHIFT (8) /* Bits 8-11: PLL Division Factor */
+#define PM_PLL_PLLDIV_MASK (15 << PM_PLL_PLLDIV_SHIFT)
+#define PM_PLL_PLLMUL_SHIFT (16) /* Bits 16-19: PLL Multiply Factor */
+#define PM_PLL_PLLMUL_MASK (15 << PM_PLL_PLLMUL_SHIFT)
+#define PM_PLL_PLLCOUNT_SHIFT (24) /* Bits 24-29: PLL Count */
+#define PM_PLL_PLLCOUNT_MASK (0x3f << PM_PLL_PLLCOUNT_SHIFT)
+
+/* Oscillator 0/1 Control Register Bit-field Definitions */
+
+#define PM_OSCCTRL_MODE_SHIFT (0) /* Bits 0-2: Oscillator Mode */
+#define PM_OSCCTRL_MODE_MASK (7 << PM_OSCCTRL_MODE_SHIFT)
+# define PM_OSCCTRL_MODE_EXT (0 << PM_OSCCTRL_MODE_SHIFT) /* External clock */
+# define PM_OSCCTRL_MODE_XTALp9 (4 << PM_OSCCTRL_MODE_SHIFT) /* Crystal XIN 0.4-0.9MHz */
+# define PM_OSCCTRL_MODE_XTAL3 (5 << PM_OSCCTRL_MODE_SHIFT) /* Crystal XIN 0.9-3.0MHz */
+# define PM_OSCCTRL_MODE_XTAL8 (6 << PM_OSCCTRL_MODE_SHIFT) /* Crystal XIN 3.0-8.0MHz */
+# define PM_OSCCTRL_MODE_XTALHI (7 << PM_OSCCTRL_MODE_SHIFT) /* Crystal XIN above 8.0MHz */
+#define PM_OSCCTRL_STARTUP_SHIFT (8) /* Bits 8-10: Oscillator Startup Time */
+#define PM_OSCCTRL_STARTUP_MASK (7 << PM_OSCCTRL_STARTUP_SHIFT)
+# define PM_OSCCTRL_STARTUP_0 (0 << PM_OSCCTRL_STARTUP_SHIFT) /* Num RCOsc cycles */
+# define PM_OSCCTRL_STARTUP_64 (1 << PM_OSCCTRL_STARTUP_SHIFT) /* " " " " " " */
+# define PM_OSCCTRL_STARTUP_128 (2 << PM_OSCCTRL_STARTUP_SHIFT) /* " " " " " " */
+# define PM_OSCCTRL_STARTUP_2K (3 << PM_OSCCTRL_STARTUP_SHIFT) /* " " " " " " */
+# define PM_OSCCTRL_STARTUP_4K (4 << PM_OSCCTRL_STARTUP_SHIFT) /* " " " " " " */
+# define PM_OSCCTRL_STARTUP_8K (5 << PM_OSCCTRL_STARTUP_SHIFT) /* " " " " " " */
+# define PM_OSCCTRL_STARTUP_16K (6 << PM_OSCCTRL_STARTUP_SHIFT) /* " " " " " " */
+
+/* Oscillator 32 Control Register Bit-field Definitions */
+
+#define PM_OSCCTRL32_EN (1 << 0) /* Bit 0: Enable the 32KHz oscillator */
+#define PM_OSCCTRL32_MODE_SHIFT (8) /* Bits 8-10: Oscillator Mode */
+#define PM_OSCCTRL32_MODE_MASK (7 << PM_OSCCTRL32_MODE_SHIFT)
+# define PM_OSCCTRL32_MODE_EXT (0 << PM_OSCCTRL32_MODE_SHIFT) /* External clock */
+# define PM_OSCCTRL32_MODE_XTAL (1 << PM_OSCCTRL32_MODE_SHIFT) /* Crystal */
+#define PM_OSCCTRL32_STARTUPSHIFT (16) /* Bits 16-18: Oscillator Startup Time */
+#define PM_OSCCTRL32_STARTUP_MASK (7 << PM_OSCCTRL32_STARTUP_SHIFT)
+# define PM_OSCCTRL32_STARTUP_0 (0 << PM_OSCCTRL32_STARTUP_SHIFT) /* Num RCOsc cycles */
+# define PM_OSCCTRL32_STARTUP_128 (1 << PM_OSCCTRL32_STARTUP_SHIFT) /* " " " " " " */
+# define PM_OSCCTRL32_STARTUP_8K (2 << PM_OSCCTRL32_STARTUP_SHIFT) /* " " " " " " */
+# define PM_OSCCTRL32_STARTUP_16K (3 << PM_OSCCTRL32_STARTUP_SHIFT) /* " " " " " " */
+# define PM_OSCCTRL32_STARTUP_64K (4 << PM_OSCCTRL32_STARTUP_SHIFT) /* " " " " " " */
+# define PM_OSCCTRL32_STARTUP_128K (5 << PM_OSCCTRL32_STARTUP_SHIFT) /* " " " " " " */
+# define PM_OSCCTRL32_STARTUP_512K (6 << PM_OSCCTRL32_STARTUP_SHIFT) /* " " " " " " */
+
+/* Interrupt Enable Register Bit-field Definitions */
+/* Interrupt Disable Register Bit-field Definitions */
+/* Interrupt Mask Register Bit-field Definitions */
+/* Interrupt Status Register Bit-field Definitions */
+/* Interrupt Clear Register Bit-field Definitions */
+
+#define PM_INT_LOCK0 (1 << 0) /* Bit 0: PLL0 locked */
+#define PM_INT_LOCK1 (1 << 1) /* Bit 1: PLL1 locked */
+#define PM_INT_CKRDY (1 << 5) /* Bit 5: Clock Ready */
+#define PM_INT_MSKRDY (1 << 6) /* Bit 6: Mask Ready */
+#define PM_INT_OSC0RDY (1 << 7) /* Bit 7: Oscillator 0 Ready */
+#define PM_INT_OSC1RDY (1 << 8) /* Bit 8: Oscillator 1 Ready */
+#define PM_INT_OSC32RDY (1 << 9) /* Bit 9: 32 KHz oscillator Ready */
+#define PM_INT_BODDET (1 << 16) /* Bit 16: Brown out detection */
+
+/* Power and Oscillators Status Register Bit-field Definitions */
+
+#define PM_POSCSR_LOCK0 (1 << 0) /* Bit 0: PLL0 locked */
+#define PM_POSCSR_LOCK1 (1 << 1) /* Bit 1: PLL1 locked */
+#define PM_POSCSR_WAKE (1 << 2) /* Bit 1: PLL1 locked */
+#define PM_POSCSR_CKRDY (1 << 5) /* Bit 5: Clock Ready */
+#define PM_POSCSR_MSKRDY (1 << 6) /* Bit 6: Mask Ready */
+#define PM_POSCSR_OSC0RDY (1 << 7) /* Bit 7: Oscillator 0 Ready */
+#define PM_POSCSR_OSC1RDY (1 << 8) /* Bit 8: Oscillator 1 Ready */
+#define PM_POSCSR_OSC32RDY (1 << 9) /* Bit 9: 32 KHz oscillator Ready */
+#define PM_POSCSR_BODDET (1 << 16) /* Bit 16: Brown out detection */
+
+/* 0x0060-0x070 Generic Clock Control Register Bit-field Definitions */
+
+#define PM_GCCTRL_OSCSEL (1 << 0) /* Bit 0: Oscillator Select */
+#define PM_GCCTRL_PLLSEL (1 << 1) /* Bit 1: PLL Select */
+#define PM_GCCTRL_CEN (1 << 2) /* Bit 2: Clock Enable */
+#define PM_GCCTRL_DIVEN (1 << 4) /* Bit 4: Divide Enable */
+#define PM_GCCTRL_DIV_SHIFT (8) /* Bits 8-15: Division Factor */
+#define PM_GCCTRL_DIV_MASK (0xff << PM_GCCTRL_DIV_SHIFT)
+
+/* RC Oscillator Calibration Register Bit-field Definitions */
+
+#define PM_RCCR_CALIB_SHIFT (0) /* Bits 0-9: Calibration Value */
+#define PM_RCCR_CALIB_MASK (0x3ff << PM_RCCR_CALIB_SHIFT)
+#define PM_RCCR_FCD (1 << 16) /* Bit 16: Flash Calibration Done */
+#define PM_RCCR_KEY_SHIFT (24) /* Bits 24-31: Register Write protection */
+#define PM_RCCR_KEY_MASK (0xff << PM_RCCR_KEY_SHIFT)
+
+/* Bandgap Calibration Register Bit-field Definitions */
+
+#define PM_BGCR_CALIB_SHIFT (0) /* Bits 0-3: Calibration Value */
+#define PM_BGCR_CALIB_MASK (7 << PM_BGCR_CALIB_SHIFT)
+#define PM_BGCR_FCD (1 << 16) /* Bit 16: Flash Calibration Done */
+#define PM_BGCR_KEY_SHIFT (24) /* Bits 24-31: Register Write protection */
+#define PM_BGCR_KEY_MASK (0xff << PM_BGCR_KEY_SHIFT)
+
+/* Linear Regulator Calibration Register Bit-field Definitions */
+
+#define PM_VREGCR_CALIB_SHIFT (0) /* Bits 0-3: Calibration Value */
+#define PM_VREGCR_CALIB_MASK (7 << PM_VREGCR_CALIB_SHIFT)
+#define PM_VREGCR_FCD (1 << 16) /* Bit 16: Flash Calibration Done */
+#define PM_VREGCR_KEY_SHIFT (24) /* Bits 24-31: Register Write protection */
+#define PM_VREGCR_KEY_MASK (0xff << PM_VREGCR_KEY_SHIFT)
+
+/* BOD Level Register BOD Read/Write Bit-field Definitions */
+
+#define PM_BOD_LEVEL_SHIFT (0) /* Bits 0-5: BOD Level */
+#define PM_BOD_LEVEL_MASK (0x3f << PM_BOD_LEVEL_SHIFT)
+#define PM_BOD_HYST (1 << 6) /* Bit 6: BOD Hysteresis */
+#define PM_BOD_CTRL_SHIFT (8) /* Bits 8-9: BOD Control */
+#define PM_BOD_CTRL_MASK (3 << PM_BOD_CTRL_SHIFT)
+# define PM_BOD_CTRL_OFF (xxx << PM_BOD_CTRL_SHIFT) /* BOD is off */
+# define PM_BOD_CTRL_RESET (xxx << PM_BOD_CTRL_SHIFT) /* BOD enabled/can reset */
+# define PM_BOD_CTRL_NORESET (xxx << PM_BOD_CTRL_SHIFT) /* BOD enabled/cannot reset */
+#define PM_BOD_FCD (1 << 16) /* Bit 16: BOD Fuse calibration done */
+#define PM_BOD_KEY_SHIFT (24) /* Bits 24-31: Register Write protection */
+#define PM_BOD_KEY_MASK (0xff << PM_BOD_KEY_SHIFT)
+
+/* Reset Cause Register */
+
+#define PM_RCAUSE_POR (1 << 0) /* Bit 0: Power-on Reset */
+#define PM_RCAUSE_BOD (1 << 1) /* Bit 1: Brown-out Reset */
+#define PM_RCAUSE_EXT (1 << 2) /* Bit 2: External Reset Pin */
+#define PM_RCAUSE_WDT (1 << 3) /* Bit 3: Watchdog Reset */
+#define PM_RCAUSE_JTAG (1 << 4) /* Bit 4: JTAG reset */
+#define PM_RCAUSE_SLEEP (1 << 6) /* Bit 6: Sleep */
+#define PM_RCAUSE_CPUERR (1 << 7) /* Bit 7: CPU Error */
+#define PM_RCAUSE_OCDRST (1 << 8) /* Bit 8: OCD Reset */
+
+/* Asynchronous Wake Up Enable Register Bit-field Definitions */
+
+#define PM_AWEN_USBWAKEN (1 << 0) /* Bit 0: USB Wake Up Enable */
+
+/* General Purpose Low-Power Register 0/1 Bit-field Definitions */
+
+/* These registers contain a 32-bit value with no smaller bit-field */
+
+/* GCLK Allocation ******************************************************************/
+
+#define AVR32_PM_GCLK0 (0) /* GCLK0 pin */
+#define AVR32_PM_GCLK1 (1) /* GCLK2 pin */
+#define AVR32_PM_GCLK2 (2) /* GCLK2 pin */
+#define AVR32_PM_GCLK_USBB (3) /* USBB */
+#define AVR32_PM_GCLK_ABDAC (4) /* ABDAC */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_AVR_SRC_AT32UC3_AT32UC3_PM_H */
+
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_pwm.h b/nuttx/arch/avr/src/at32uc3/at32uc3_pwm.h
new file mode 100644
index 000000000..e2dee47e5
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_pwm.h
@@ -0,0 +1,222 @@
+/************************************************************************************
+ * arch/avr/src/at32uc3/at32uc3_pwm.h
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_AVR_SRC_AT32UC3_AT32UC3_PWM_H
+#define __ARCH_AVR_SRC_AT32UC3_AT32UC3_PWM_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* PWM Channel Offsets **************************************************************/
+
+#define AVR32_PWM_CHAN_OFFSET(n) (0x200+((n)<<5))
+#define AVR32_PWM_CHAN0_OFFSET (0x200)
+#define AVR32_PWM_CHAN1_OFFSET (0x220)
+
+/* Register offsets *****************************************************************/
+
+#define AVR32_PWM_MR_OFFSET 0x000 /* PWM Mode Register */
+#define AVR32_PWM_ENA_OFFSET 0x004 /* PWM Enable Register */
+#define AVR32_PWM_DIS_OFFSET 0x008 /* PWM Disable Register */
+#define AVR32_PWM_SR_OFFSET 0x00c /* PWM Status Register */
+#define AVR32_PWM_IER_OFFSET 0x010 /* PWM Interrupt Enable Register */
+#define AVR32_PWM_IDR_OFFSET 0x014 /* PWM Interrupt Disable Register */
+#define AVR32_PWM_IMR_OFFSET 0x018 /* PWM Interrupt Mask Register */
+#define AVR32_PWM_ISR_OFFSET 0x01c /* PWM Interrupt Status Register */
+
+#define AVR32_PWM_CMR_OFFSET 0x000 /* Channel Mode Register */
+#define AVR32_PWM_CDTY_OFFSET 0x004 /* Channel Duty Cycle Register */
+#define AVR32_PWM_CPRD_OFFSET 0x008 /* Channel Period Register */
+#define AVR32_PWM_CCNT_OFFSET 0x00c /* Channel Counter Register */
+#define AVR32_PWM_CUPD_OFFSET 0x010 /* Channel Update Register */
+
+#define AVR32_PWMCH_CMR_OFFSET(n) (AVR32_PWM_CHAN_OFFSET(n)+PWM_CMR_OFFSET)
+#define AVR32_PWMCH_CDTY_OFFSET(n) (AVR32_PWM_CHAN_OFFSET(n)+PWM_CDTY_OFFSET)
+#define AVR32_PWMCH_CPRD_OFFSET(n) (AVR32_PWM_CHAN_OFFSET(n)+PWM_CPRD_OFFSET)
+#define AVR32_PWMCH_CCNT_OFFSET(n) (AVR32_PWM_CHAN_OFFSET(n)+PWM_CCNT_OFFSET)
+#define AVR32_PWMCH_CUPD_OFFSET(n) (AVR32_PWM_CHAN_OFFSET(n)+PWM_CUPD_OFFSET)
+
+#define AVR32_PWMCH0_CMR_OFFSET (AVR32_PWM_CHAN0_OFFSET+PWM_CMR_OFFSET)
+#define AVR32_PWMCH0_CDTY_OFFSET (AVR32_PWM_CHAN0_OFFSET+PWM_CDTY_OFFSET)
+#define AVR32_PWMCH0_CPRD_OFFSET (AVR32_PWM_CHAN0_OFFSET+PWM_CPRD_OFFSET)
+#define AVR32_PWMCH0_CCNT_OFFSET (AVR32_PWM_CHAN0_OFFSET+PWM_CCNT_OFFSET)
+#define AVR32_PWMCH0_CUPD_OFFSET (AVR32_PWM_CHAN0_OFFSET+PWM_CUPD_OFFSET)
+
+#define AVR32_PWMCH1_CMR_OFFSET (AVR32_PWM_CHAN1_OFFSET+PWM_CMR_OFFSET)
+#define AVR32_PWMCH1_CDTY_OFFSET (AVR32_PWM_CHAN1_OFFSET+PWM_CDTY_OFFSET)
+#define AVR32_PWMCH1_CPRD_OFFSET (AVR32_PWM_CHAN1_OFFSET+PWM_CPRD_OFFSET)
+#define AVR32_PWMCH1_CCNT_OFFSET (AVR32_PWM_CHAN1_OFFSET+PWM_CCNT_OFFSET)
+#define AVR32_PWMCH1_CUPD_OFFSET (AVR32_PWM_CHAN1_OFFSET+PWM_CUPD_OFFSET)
+
+/* PWM Channel Base Addresses *******************************************************/
+
+#define AVR32_PWM_CHAN_BASE(n) (AVR32_PWM_BASE+PWM_CHAN_OFFSET(n))
+#define AVR32_PWM_CHAN0_BASE (AVR32_PWM_BASE+PWM_CHAN0_OFFSET)
+#define AVR32_PWM_CHAN1_BASE (AVR32_PWM_BASE+PWM_CHAN1_OFFSET)
+
+/* Register Addresses ***************************************************************/
+
+#define AVR32_PWM_MR (AVR32_PWM_BASE+AVR32_PWM_MR_OFFSET)
+#define AVR32_PWM_ENA (AVR32_PWM_BASE+AVR32_PWM_ENA_OFFSET)
+#define AVR32_PWM_DIS (AVR32_PWM_BASE+AVR32_PWM_DIS_OFFSET)
+#define AVR32_PWM_SR (AVR32_PWM_BASE+AVR32_PWM_SR_OFFSET)
+#define AVR32_PWM_IER (AVR32_PWM_BASE+AVR32_PWM_IER_OFFSET)
+#define AVR32_PWM_IDR (AVR32_PWM_BASE+AVR32_PWM_IDR_OFFSET)
+#define AVR32_PWM_IMR (AVR32_PWM_BASE+AVR32_PWM_IMR_OFFSET)
+#define AVR32_PWM_ISR (AVR32_PWM_BASE+AVR32_PWM_ISR_OFFSET)
+
+#define AVR32_PWMCH_CMR(n) (AVR32_PWM_CHAN_BASE(n)+PWM_CMR_OFFSET)
+#define AVR32_PWMCH_CDTY(n) (AVR32_PWM_CHAN_BASE(n)+PWM_CDTY_OFFSET)
+#define AVR32_PWMCH_CPRD(n) (AVR32_PWM_CHAN_BASE(n)+PWM_CPRD_OFFSET)
+#define AVR32_PWMCH_CCNT(n) (AVR32_PWM_CHAN_BASE(n)+PWM_CCNT_OFFSET)
+#define AVR32_PWMCH_CUPD(n) (AVR32_PWM_CHAN_BASE(n)+PWM_CUPD_OFFSET)
+
+#define AVR32_PWMCH0_CMR (AVR32_PWM_CHAN0_BASE+PWM_CMR_OFFSET)
+#define AVR32_PWMCH0_CDTY (AVR32_PWM_CHAN0_BASE+PWM_CDTY_OFFSET)
+#define AVR32_PWMCH0_CPRD (AVR32_PWM_CHAN0_BASE+PWM_CPRD_OFFSET)
+#define AVR32_PWMCH0_CCNT (AVR32_PWM_CHAN0_BASE+PWM_CCNT_OFFSET)
+#define AVR32_PWMCH0_CUPD (AVR32_PWM_CHAN0_BASE+PWM_CUPD_OFFSET)
+
+#define AVR32_PWMCH1_CMR (AVR32_PWM_CHAN1_BASE+PWM_CMR_OFFSET)
+#define AVR32_PWMCH1_CDTY (AVR32_PWM_CHAN1_BASE+PWM_CDTY_OFFSET)
+#define AVR32_PWMCH1_CPRD (AVR32_PWM_CHAN1_BASE+PWM_CPRD_OFFSET)
+#define AVR32_PWMCH1_CCNT (AVR32_PWM_CHAN1_BASE+PWM_CCNT_OFFSET)
+#define AVR32_PWMCH1_CUPD (AVR32_PWM_CHAN1_BASE+PWM_CUPD_OFFSET)
+
+/* Register Bit-field Definitions ***************************************************/
+
+/* PWM Mode Register Bit-field Definitions */
+
+#define PWM_MR_DIVA_SHIFT (0) /* Bits 0-7: CLKA Divide Factor */
+#define PWM_MR_DIVA_MASK (0xff << PWM_MR_DIVA_SHIFT)
+# define PWM_MR_DIVA_OFF (0 << PWM_MR_DIVA_SHIFT)
+# define PWM_MR_DIVA(n) ((n) << PWM_MR_DIVA_SHIFT)
+#define PWM_MR_PREA_SHIFT (8) /* Bits 8-11 */
+#define PWM_MR_PREA_MASK (15 << PWM_MR_PREA_SHIFT)
+# define PWM_MR_PREA_MCK (0 << PWM_MR_PREA_SHIFT) /* MCK */
+# define PWM_MR_PREA_MCKDIV2 (1 << PWM_MR_PREA_SHIFT) /* MCK/2 */
+# define PWM_MR_PREA_MCKDIV4 (2 << PWM_MR_PREA_SHIFT) /* MCK/4 */
+# define PWM_MR_PREA_MCKDIV8 (3 << PWM_MR_PREA_SHIFT) /* MCK/8 */
+# define PWM_MR_PREA_MCKDIV16 (4 << PWM_MR_PREA_SHIFT) /* MCK/16 */
+# define PWM_MR_PREA_MCKDIV32 (5 << PWM_MR_PREA_SHIFT) /* MCK/32 */
+# define PWM_MR_PREA_MCKDIV64 (6 << PWM_MR_PREA_SHIFT) /* MCK/64 */
+# define PWM_MR_PREA_MCKDIV128 (7 << PWM_MR_PREA_SHIFT) /* MCK/128 */
+# define PWM_MR_PREA_MCKDIV256 (8 << PWM_MR_PREA_SHIFT) /* MCK/256 */
+# define PWM_MR_PREA_MCKDIV512 (9 << PWM_MR_PREA_SHIFT) /* MCK/512 */
+# define PWM_MR_PREA_MCKDIV1024 (10 << PWM_MR_PREA_SHIFT) /* MCK/1024 */
+#define PWM_MR_DIVB_SHIFT (16) /* Bits 16-23: CLKB Divide Factor */
+#define PWM_MR_DIVB_MASK (0xff << PWM_MR_DIVB_SHIFT)
+# define PWM_MR_DIVB_OFF (0 << PWM_MR_DIVB_SHIFT)
+# define PWM_MR_DIVB(n) ((n) << PWM_MR_DIVB_SHIFT)
+#define PWM_MR_PREB_SHIFT (24) /* Bits 24-27 */
+#define PWM_MR_PREB_MASK (15 << PWM_MR_PREB_SHIFT)
+# define PWM_MR_PREB_MCK (0 << PWM_MR_PREB_SHIFT) /* MCK */
+# define PWM_MR_PREB_MCKDIV2 (1 << PWM_MR_PREB_SHIFT) /* MCK/2 */
+# define PWM_MR_PREB_MCKDIV4 (2 << PWM_MR_PREB_SHIFT) /* MCK/4 */
+# define PWM_MR_PREB_MCKDIV8 (3 << PWM_MR_PREB_SHIFT) /* MCK/8 */
+# define PWM_MR_PREB_MCKDIV16 (4 << PWM_MR_PREB_SHIFT) /* MCK/16 */
+# define PWM_MR_PREB_MCKDIV32 (5 << PWM_MR_PREB_SHIFT) /* MCK/32 */
+# define PWM_MR_PREB_MCKDIV64 (6 << PWM_MR_PREB_SHIFT) /* MCK/64 */
+# define PWM_MR_PREB_MCKDIV128 (7 << PWM_MR_PREB_SHIFT) /* MCK/128 */
+# define PWM_MR_PREB_MCKDIV256 (8 << PWM_MR_PREB_SHIFT) /* MCK/256 */
+# define PWM_MR_PREB_MCKDIV512 (9 << PWM_MR_PREB_SHIFT) /* MCK/512 */
+# define PWM_MR_PREB_MCKDIV1024 (10 << PWM_MR_PREB_SHIFT) /* MCK/1024 */
+
+/* PWM Enable Register Bit-field Definitions */
+/* PWM Disable Register Bit-field Definitions */
+/* PWM Status Register Bit-field Definitions */
+/* PWM Interrupt Enable Register Bit-field Definitions */
+/* PWM Interrupt Disable Register Bit-field Definitions */
+/* PWM Interrupt Mask Register Bit-field Definitions */
+/* PWM Interrupt Status Register Bit-field Definitions */
+
+#define PWM_CHID(n) (1 << (n)) /* Bit n: Channel ID n */
+#define PWM_CHID0 (1 << 0) /* Bit 0: Channel ID 0 */
+#define PWM_CHID1 (1 << 1) /* Bit 1: Channel ID 1 */
+#define PWM_CHID2 (1 << 2) /* Bit 2: Channel ID 2 */
+#define PWM_CHID3 (1 << 3) /* Bit 3: Channel ID 3 */
+#define PWM_CHID4 (1 << 4) /* Bit 4: Channel ID 4 */
+#define PWM_CHID5 (1 << 5) /* Bit 5: Channel ID 5 */
+#define PWM_CHID6 (1 << 6) /* Bit 6: Channel ID 6 */
+
+/* Channel Mode Register Bit-field Definitions */
+
+#define PWM_CMR_CPRE_SHIFT (0) /* Bits 0-3: CLKA Divide FactorChannel Pre-scaler */
+#define PWM_CMR_CPRE_MASK (15 << PWM_CMR_CPRE_SHIFT)
+# define PWM_CMR_CPRE_MCK (0 << PWM_CMR_CPRE_SHIFT) /* MCK */
+# define PWM_CMR_CPRE_MCKDIV2 (1 << PWM_CMR_CPRE_SHIFT) /* MCK/2 */
+# define PWM_CMR_CPRE_MCKDIV4 (2 << PWM_CMR_CPRE_SHIFT) /* MCK/4 */
+# define PWM_CMR_CPRE_MCKDIV8 (3 << PWM_CMR_CPRE_SHIFT) /* MCK/8 */
+# define PWM_CMR_CPRE_MCKDIV16 (4 << PWM_CMR_CPRE_SHIFT) /* MCK/16 */
+# define PWM_CMR_CPRE_MCKDIV32 (5 << PWM_CMR_CPRE_SHIFT) /* MCK/32 */
+# define PWM_CMR_CPRE_MCKDIV64 (6 << PWM_CMR_CPRE_SHIFT) /* MCK/64 */
+# define PWM_CMR_CPRE_MCKDIV128 (7 << PWM_CMR_CPRE_SHIFT) /* MCK/128 */
+# define PWM_CMR_CPRE_MCKDIV256 (8 << PWM_CMR_CPRE_SHIFT) /* MCK/256 */
+# define PWM_CMR_CPRE_MCKDIV512 (9 << PWM_CMR_CPRE_SHIFT) /* MCK/512 */
+# define PWM_CMR_CPRE_MCKDIV1024 (10 << PWM_CMR_CPRE_SHIFT) /* MCK/1024 */
+# define PWM_CMR_CPRE_CLKA (11 << PWM_CMR_CPRE_SHIFT) /* CLKA */
+# define PWM_CMR_CPRE_CLKB (12 << PWM_CMR_CPRE_SHIFT) /* CLB */
+#define PWM_CMR_CALG (1 << 8) /* Bit 8: Channel Alignment */
+#define PWM_CMR_CPOL (1 << 9) /* Bit 9: Channel Polarity */
+#define PWM_CMR_CPD (1 << 10) /* Bit 10: Channel Update Period */
+
+/* Channel Duty Cycle Register Bit-field Definitions */
+/* Channel Period Register Bit-field Definitions */
+/* Channel Counter Register Bit-field Definitions */
+/* Channel Update Register Bit-field Definitions */
+
+/* These registers hold a 32-bit value with bit-fiels */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_AVR_SRC_AT32UC3_AT32UC3_PWM_H */
+
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_rtc.h b/nuttx/arch/avr/src/at32uc3/at32uc3_rtc.h
new file mode 100644
index 000000000..1a861d0bc
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_rtc.h
@@ -0,0 +1,112 @@
+/************************************************************************************
+ * arch/avr/src/at32uc3/at32uc3_rtc.h
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_AVR_SRC_AT32UC3_AT32UC3_RTC_H
+#define __ARCH_AVR_SRC_AT32UC3_AT32UC3_RTC_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+
+#define AVR32_RTC_CTRL_OFFSET 0x00 /* Control Register */
+#define AVR32_RTC_VAL_OFFSET 0x04 /* Value Register */
+#define AVR32_RTC_TOP_OFFSET 0x08 /* Top Register */
+#define AVR32_RTC_IER_OFFSET 0x10 /* Interrupt Enable Register */
+#define AVR32_RTC_IDR_OFFSET 0x14 /* Interrupt Disable Register */
+#define AVR32_RTC_IMR_OFFSET 0x18 /* Interrupt Mask Register */
+#define AVR32_RTC_ISR_OFFSET 0x1c /* Interrupt Status Register */
+#define AVR32_RTC_ICR_OFFSET 0x20 /* Interrupt Clear Register */
+
+/* Register Addresses ***************************************************************/
+
+#define AVR32_RTC_CTRL (AVR32_RTC_BASE+AVR32_RTC_CTRL_OFFSET)
+#define AVR32_RTC_VAL (AVR32_RTC_BASE+AVR32_RTC_VAL_OFFSET)
+#define AVR32_RTC_TOP (AVR32_RTC_BASE+AVR32_RTC_TOP_OFFSET)
+#define AVR32_RTC_IER (AVR32_RTC_BASE+AVR32_RTC_IER_OFFSET)
+#define AVR32_RTC_IDR (AVR32_RTC_BASE+AVR32_RTC_IDR_OFFSET)
+#define AVR32_RTC_IMR (AVR32_RTC_BASE+AVR32_RTC_IMR_OFFSET)
+#define AVR32_RTC_ISR (AVR32_RTC_BASE+AVR32_RTC_ISR_OFFSET)
+#define AVR32_RTC_ICR (AVR32_RTC_BASE+AVR32_RTC_ICR_OFFSET)
+
+/* Register Bit-field Definitions ***************************************************/
+
+/* Control Register Bit-field Definitions */
+
+#define RTC_CTRL_EN (1 << 0) /* Bit 0: Enable */
+#define RTC_CTRL_PCLR (1 << 1) /* Bit 1: Prescaler Clear */
+#define RTC_CTRL_WAKEN (1 << 2) /* Bit 2: Wakeup Enable */
+#define RTC_CTRL_CLK32 (1 << 3) /* Bit 3: 32 KHz Oscillator Select */
+#define RTC_CTRL_BUSY (1 << 4) /* Bit 4: RTC Busy */
+#define RTC_CTRL_PSEL_SHIFT (8) /* Bits 8-11: Prescale Select */
+#define RTC_CTRL_PSEL_MASK (15 << RTC_CTRL_PSEL_SHIFT)
+#define RTC_CTRL_CLKEN (1 << 16) /* Bit 16: Clock Enable */
+
+/* Value Register Bit-field Definitions */
+/* This is a 32-bit data register and, hence, has no bit field */
+
+/* Top Register Bit-field Definitions */
+/* This is a 32-bit data register and, hence, has no bit field */
+
+/* Interrupt Enable Register Bit-field Definitions
+ * Interrupt Disable Register Bit-field Definitions
+ * Interrupt Mask Register Bit-field Definitions
+ * Interrupt Status Register Bit-field Definitions
+ * Interrupt Clear Register Bit-field Definitions
+ */
+
+#define RTC_INT_TOPI (1 << 0) /* Bit 0: Top interrupt */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_AVR_SRC_AT32UC3_AT32UC3_RTC_H */
+
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_serial.c b/nuttx/arch/avr/src/at32uc3/at32uc3_serial.c
new file mode 100644
index 000000000..7ed9d4b95
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_serial.c
@@ -0,0 +1,839 @@
+/****************************************************************************
+ * arch/avr/src/at32uc3/at32uc3_serial.c
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <unistd.h>
+#include <semaphore.h>
+#include <string.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+#include <nuttx/serial.h>
+
+#include <arch/board/board.h>
+
+#include "at32uc3_config.h"
+#include "chip.h"
+#include "at32uc3_usart.h"
+#include "up_arch.h"
+#include "up_internal.h"
+#include "os_internal.h"
+#include "at32uc3_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* Some sanity checks *******************************************************/
+
+/* Is there at least one USART enabled and configured as a RS-232 device? */
+
+#ifndef HAVE_RS232_DEVICE
+# warning "No USARTs enabled as RS-232 devices"
+#endif
+
+/* If we are not using the serial driver for the console, then we still must
+ * provide some minimal implementation of up_putc.
+ */
+
+#ifdef CONFIG_USE_SERIALDRIVER
+
+/* Which USART with be tty0/console and which tty1? */
+
+#if defined(CONFIG_USART0_SERIAL_CONSOLE)
+# define CONSOLE_DEV g_usart0port /* USART0 is console */
+# define TTYS0_DEV g_usart0port /* USART0 is ttyS0 */
+# ifdef CONFIG_AVR32_USART1_RS232
+# define TTYS1_DEV g_usart1port /* USART1 is ttyS1 */
+# ifdef CONFIG_AVR32_USART2_RS232
+# define TTYS2_DEV g_usart2port /* USART2 is ttyS2 */
+# else
+# undef TTYS2_DEV /* No ttyS2 */
+# endif
+# else
+# ifdef CONFIG_AVR32_USART2_RS232
+# define TTYS1_DEV g_usart2port /* USART2 is ttyS1 */
+# else
+# undef TTYS1_DEV /* No ttyS1 */
+# endif
+# undef TTYS2_DEV /* No ttyS2 */
+# endif
+#elif defined(CONFIG_USART1_SERIAL_CONSOLE)
+# define CONSOLE_DEV g_usart1port /* USART1 is console */
+# define TTYS0_DEV g_usart1port /* USART1 is ttyS0 */
+# ifdef CONFIG_AVR32_USART0_RS232
+# define TTYS1_DEV g_usart0port /* USART0 is ttyS1 */
+# ifdef CONFIG_AVR32_USART2_RS232
+# define TTYS2_DEV g_usart2port /* USART2 is ttyS2 */
+# else
+# undef TTYS2_DEV /* No ttyS2 */
+# endif
+# else
+# ifdef CONFIG_AVR32_USART2_RS232
+# define TTYS1_DEV g_usart2port /* USART2 is ttyS1 */
+# else
+# undef TTYS1_DEV /* No ttyS1 */
+# endif
+# undef TTYS2_DEV /* No ttyS2 */
+# endif
+#elif defined(CONFIG_USART2_SERIAL_CONSOLE)
+# define CONSOLE_DEV g_usart2port /* USART2 is console */
+# define TTYS0_DEV g_usart2port /* USART2 is ttyS0 */
+# ifdef CONFIG_AVR32_USART0_RS232
+# define TTYS1_DEV g_usart0port /* USART0 is ttyS1 */
+# ifdef CONFIG_AVR32_USART1_RS232
+# define TTYS2_DEV g_usart1port /* USART1 is ttyS2 */
+# else
+# undef TTYS2_DEV /* No ttyS2 */
+# endif
+# else
+# ifdef CONFIG_AVR32_USART1_RS232
+# define TTYS1_DEV g_usart1port /* USART1 is ttyS1 */
+# else
+# undef TTYS1_DEV /* No ttyS1 */
+# endif
+# undef TTYS2_DEV /* No ttyS2 */
+# endif
+#endif
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+struct up_dev_s
+{
+ uintptr_t usartbase; /* Base address of USART registers */
+ uint32_t baud; /* Configured baud */
+ 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 (5, 6, 7 or 8) */
+ bool stopbits2; /* true: Configure with 2 stop bits instead of 1 */
+};
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+static int up_setup(struct uart_dev_s *dev);
+static void up_shutdown(struct uart_dev_s *dev);
+static int up_attach(struct uart_dev_s *dev);
+static void up_detach(struct uart_dev_s *dev);
+static int up_interrupt(int irq, void *context);
+static int up_ioctl(struct file *filep, int cmd, unsigned long arg);
+static int up_receive(struct uart_dev_s *dev, uint32_t *status);
+static void up_rxint(struct uart_dev_s *dev, bool enable);
+static bool up_rxavailable(struct uart_dev_s *dev);
+static void up_send(struct uart_dev_s *dev, int ch);
+static void up_txint(struct uart_dev_s *dev, bool enable);
+static bool up_txready(struct uart_dev_s *dev);
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+struct uart_ops_s g_uart_ops =
+{
+ .setup = up_setup,
+ .shutdown = up_shutdown,
+ .attach = up_attach,
+ .detach = up_detach,
+ .ioctl = up_ioctl,
+ .receive = up_receive,
+ .rxint = up_rxint,
+ .rxavailable = up_rxavailable,
+ .send = up_send,
+ .txint = up_txint,
+ .txready = up_txready,
+ .txempty = up_txready,
+};
+
+/* I/O buffers */
+
+#ifdef CONFIG_AVR32_USART0_RS232
+static char g_usart0rxbuffer[CONFIG_USART0_RXBUFSIZE];
+static char g_usart0txbuffer[CONFIG_USART0_TXBUFSIZE];
+#endif
+#ifdef CONFIG_AVR32_USART1_RS232
+static char g_usart1rxbuffer[CONFIG_USART1_RXBUFSIZE];
+static char g_usart1txbuffer[CONFIG_USART1_TXBUFSIZE];
+#endif
+#ifdef CONFIG_AVR32_USART2_RS232
+static char g_usart2rxbuffer[CONFIG_USART2_RXBUFSIZE];
+static char g_usart2txbuffer[CONFIG_USART2_TXBUFSIZE];
+#endif
+
+/* This describes the state of the AVR32 USART0 ports. */
+
+#ifdef CONFIG_AVR32_USART0_RS232
+static struct up_dev_s g_usart0priv =
+{
+ .usartbase = AVR32_USART0_BASE,
+ .baud = CONFIG_USART0_BAUD,
+ .irq = AVR32_IRQ_USART0,
+ .parity = CONFIG_USART0_PARITY,
+ .bits = CONFIG_USART0_BITS,
+ .stopbits2 = CONFIG_USART0_2STOP,
+};
+
+static uart_dev_t g_usart0port =
+{
+ .recv =
+ {
+ .size = CONFIG_USART0_RXBUFSIZE,
+ .buffer = g_usart0rxbuffer,
+ },
+ .xmit =
+ {
+ .size = CONFIG_USART0_TXBUFSIZE,
+ .buffer = g_usart0txbuffer,
+ },
+ .ops = &g_uart_ops,
+ .priv = &g_usart0priv,
+};
+#endif
+
+/* This describes the state of the AVR32 USART1 port. */
+
+#ifdef CONFIG_AVR32_USART1_RS232
+static struct up_dev_s g_usart1priv =
+{
+ .usartbase = AVR32_USART1_BASE,
+ .baud = CONFIG_USART1_BAUD,
+ .irq = AVR32_IRQ_USART1,
+ .parity = CONFIG_USART1_PARITY,
+ .bits = CONFIG_USART1_BITS,
+ .stopbits2 = CONFIG_USART1_2STOP,
+};
+
+static uart_dev_t g_usart1port =
+{
+ .recv =
+ {
+ .size = CONFIG_USART1_RXBUFSIZE,
+ .buffer = g_usart1rxbuffer,
+ },
+ .xmit =
+ {
+ .size = CONFIG_USART1_TXBUFSIZE,
+ .buffer = g_usart1txbuffer,
+ },
+ .ops = &g_uart_ops,
+ .priv = &g_usart1priv,
+};
+#endif
+
+/* This describes the state of the AVR32 USART2 port. */
+
+#ifdef CONFIG_AVR32_USART2_RS232
+static struct up_dev_s g_usart2priv =
+{
+ .usartbase = AVR32_USART2_BASE,
+ .baud = CONFIG_USART2_BAUD,
+ .irq = AVR32_IRQ_USART2,
+ .parity = CONFIG_USART2_PARITY,
+ .bits = CONFIG_USART2_BITS,
+ .stopbits2 = CONFIG_USART2_2STOP,
+};
+
+static uart_dev_t g_usart2port =
+{
+ .recv =
+ {
+ .size = CONFIG_USART2_RXBUFSIZE,
+ .buffer = g_usart2rxbuffer,
+ },
+ .xmit =
+ {
+ .size = CONFIG_USART2_TXBUFSIZE,
+ .buffer = g_usart2txbuffer,
+ },
+ .ops = &g_uart_ops,
+ .priv = &g_usart2priv,
+};
+#endif
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_serialin
+ ****************************************************************************/
+
+static inline uint32_t up_serialin(struct up_dev_s *priv, int offset)
+{
+ return getreg32(priv->usartbase + offset);
+}
+
+/****************************************************************************
+ * Name: up_serialout
+ ****************************************************************************/
+
+static inline void up_serialout(struct up_dev_s *priv, int offset, uint32_t value)
+{
+ putreg32(value, priv->usartbase + offset);
+}
+
+/****************************************************************************
+ * Name: up_restoreusartint
+ ****************************************************************************/
+
+static void up_restoreusartint(struct up_dev_s *priv, uint32_t imr)
+{
+ /* Re-enable interrupts as for each "1" bit in imr */
+
+ up_serialout(priv, AVR32_USART_IER_OFFSET, imr);
+}
+
+/****************************************************************************
+ * Name: up_disableusartint
+ ****************************************************************************/
+
+static inline void up_disableusartint(struct up_dev_s *priv, uint32_t *imr)
+{
+ if (imr)
+ {
+ *imr = up_serialin(priv, AVR32_USART_IDR_OFFSET);
+ }
+
+ /* Disable all interrupts */
+
+ up_serialout(priv, AVR32_USART_IDR_OFFSET, USART_INT_ALL);
+}
+
+/****************************************************************************
+ * Name: up_setup
+ *
+ * Description:
+ * Configure the USART baud, bits, parity, etc. This method is called the
+ * first time that the serial port is opened.
+ *
+ ****************************************************************************/
+
+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;
+
+ /* Configure the USART as an RS-232 UART */
+
+ usart_configure(priv->usartbase, priv->baud, priv->parity,
+ priv->bits, priv->stopbits2);
+#endif
+
+ return OK;
+}
+
+/****************************************************************************
+ * Name: up_shutdown
+ *
+ * Description:
+ * Disable the USART. This method is called when the serial
+ * port is closed
+ *
+ ****************************************************************************/
+
+static void up_shutdown(struct uart_dev_s *dev)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+
+ /* Reset, disable interrupts, and disable Rx and Tx */
+
+ usart_reset(priv->usartbase);
+}
+
+/****************************************************************************
+ * Name: up_attach
+ *
+ * Description:
+ * Configure the USART to operation in interrupt driven mode. This method is
+ * called when the serial port is opened. Normally, this is just after the
+ * the setup() method is called, however, the serial console may operate in
+ * a non-interrupt driven mode during the boot phase.
+ *
+ * RX and TX interrupts are not enabled when by the attach method (unless the
+ * hardware supports multiple levels of interrupt enabling). The RX and TX
+ * interrupts are not enabled until the txint() and rxint() methods are called.
+ *
+ ****************************************************************************/
+
+static int up_attach(struct uart_dev_s *dev)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+
+ /* Attach the IRQ */
+
+ return irq_attach(priv->irq, up_interrupt);
+}
+
+/****************************************************************************
+ * Name: up_detach
+ *
+ * Description:
+ * Detach USART interrupts. This method is called when the serial port is
+ * closed normally just before the shutdown method is called. The exception
+ * is the serial console which is never shutdown.
+ *
+ ****************************************************************************/
+
+static void up_detach(struct uart_dev_s *dev)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ up_serialout(priv, AVR32_USART_IDR_OFFSET, 0xffffffff);
+ irq_detach(priv->irq);
+}
+
+/****************************************************************************
+ * Name: up_interrupt
+ *
+ * Description:
+ * This is the USART interrupt handler. It will be invoked when an
+ * interrupt received on the 'irq' It should call uart_transmitchars or
+ * uart_receivechar to perform the appropriate data transfers. The
+ * interrupt handling logic must be able to map the 'irq' number into the
+ * approprite uart_dev_s structure in order to call these functions.
+ *
+ ****************************************************************************/
+
+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;
+
+#ifdef CONFIG_AVR32_USART0_RS232
+ if (g_usart0priv.irq == irq)
+ {
+ dev = &g_usart0port;
+ }
+ else
+#endif
+#ifdef CONFIG_AVR32_USART1_RS232
+ if (g_usart1priv.irq == irq)
+ {
+ dev = &g_usart1port;
+ }
+ else
+#endif
+#ifdef CONFIG_AVR32_USART2_RS232
+ if (g_usart2priv.irq == irq)
+ {
+ dev = &g_usart2port;
+ }
+ else
+#endif
+ {
+ 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.
+ */
+
+ handled = true;
+ for (passes = 0; passes < 256 && handled; passes++)
+ {
+ handled = false;
+
+ /* 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) */
+
+ if ((csr & (USART_CSR_RXRDY|USART_CSR_TIMEOUT)) != 0)
+ {
+ /* Received data ready... process incoming bytes */
+
+ uart_recvchars(dev);
+ handled = true;
+ }
+
+ /* Handle outgoing, transmit bytes */
+
+ if ((csr & USART_CSR_TXRDY) != 0)
+ {
+ /* Transmit data regiser empty ... process outgoing bytes */
+
+ uart_xmitchars(dev);
+ handled = true;
+ }
+ }
+ return OK;
+}
+
+/****************************************************************************
+ * Name: up_ioctl
+ *
+ * Description:
+ * All ioctl calls will be routed through this method
+ *
+ ****************************************************************************/
+
+static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
+{
+#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 xxx: /* Add commands here */
+ break;
+
+ default:
+ ret = -ENOTTY;
+ break;
+ }
+
+ return ret;
+#else
+ return -ENOTTY;
+#endif
+}
+
+/****************************************************************************
+ * Name: up_receive
+ *
+ * Description:
+ * Called (usually) from the interrupt level to receive one
+ * character from the USART. Error bits associated with the
+ * receipt are provided in the return 'status'.
+ *
+ ****************************************************************************/
+
+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 rhr;
+
+ /* Get the Rx byte. The USART Rx interrupt flag is cleared by side effect
+ * when reading the received character.
+ */
+
+ rhr = up_serialin(priv, AVR32_USART_RHR_OFFSET);
+
+ /* Return status information */
+
+ if (status)
+ {
+ *status = priv->csr;
+ }
+ priv->csr = 0;
+
+ /* Then return the actual received byte */
+
+ return rhr & USART_RHR_RXCHR_MASK;
+}
+
+/****************************************************************************
+ * Name: up_rxint
+ *
+ * Description:
+ * Call to enable or disable RX interrupts
+ *
+ ****************************************************************************/
+
+static void up_rxint(struct uart_dev_s *dev, bool enable)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+
+ if (enable)
+ {
+ /* Receive an interrupt when their is anything in the Rx data register (or an Rx
+ * timeout occurs).
+ */
+
+#ifndef CONFIG_SUPPRESS_SERIAL_INTS
+# 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
+ {
+ up_serialout(priv, AVR32_USART_IDR_OFFSET,
+ USART_INT_RXRDY|USART_INT_TIMEOUT|
+ USART_INT_OVRE|USART_INT_FRAME|USART_INT_PARE);
+ }
+}
+
+/****************************************************************************
+ * Name: up_rxavailable
+ *
+ * Description:
+ * Return true if the receive register is not empty
+ *
+ ****************************************************************************/
+
+static bool up_rxavailable(struct uart_dev_s *dev)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ 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.
+ *
+ ****************************************************************************/
+
+static void up_send(struct uart_dev_s *dev, int ch)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ up_serialout(priv, AVR32_USART_THR_OFFSET, (uint32_t)ch);
+}
+
+/****************************************************************************
+ * Name: up_txint
+ *
+ * Description:
+ * Call to enable or disable TX interrupts
+ *
+ ****************************************************************************/
+
+static void up_txint(struct uart_dev_s *dev, bool enable)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ irqstate_t flags;
+
+ flags = irqsave();
+ if (enable)
+ {
+ /* Set to receive an interrupt when the TX data register is empty */
+
+#ifndef CONFIG_SUPPRESS_SERIAL_INTS
+ 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).
+ */
+
+ uart_xmitchars(dev);
+#endif
+ }
+ else
+ {
+ /* Disable the TX interrupt */
+
+ up_serialout(priv, AVR32_USART_IDR_OFFSET, USART_INT_TXRDY);
+ }
+ irqrestore(flags);
+}
+
+/****************************************************************************
+ * Name: up_txready
+ *
+ * Description:
+ * Return true if the tranmsit data register is empty
+ *
+ ****************************************************************************/
+
+static bool up_txready(struct uart_dev_s *dev)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ 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;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_earlyserialinit
+ *
+ * Description:
+ * Performs the low level USART initialization early in debug so that the
+ * serial console will be available during bootup. This must be called
+ * before up_serialinit. NOTE: This function depends on GPIO pin
+ * configuration performed in up_consoleinit() and main clock iniialization
+ * performed in up_clkinitialize().
+ *
+ ****************************************************************************/
+
+void up_earlyserialinit(void)
+{
+ /* Disable all USARTS */
+
+ up_disableusartint(TTYS0_DEV.priv, NULL);
+#ifdef TTYS1_DEV
+ up_disableusartint(TTYS1_DEV.priv, NULL);
+#endif
+#ifdef TTYS2_DEV
+ up_disableusartint(TTYS2_DEV.priv, NULL);
+#endif
+
+ /* Configuration whichever one is the console */
+
+#ifdef HAVE_SERIAL_CONSOLE
+ CONSOLE_DEV.isconsole = true;
+ up_setup(&CONSOLE_DEV);
+#endif
+}
+
+/****************************************************************************
+ * Name: up_serialinit
+ *
+ * Description:
+ * Register serial console and serial ports. This assumes
+ * that up_earlyserialinit was called previously.
+ *
+ ****************************************************************************/
+
+void up_serialinit(void)
+{
+ /* Register the console */
+
+#ifdef HAVE_SERIAL_CONSOLE
+ (void)uart_register("/dev/console", &CONSOLE_DEV);
+#endif
+
+ /* Register all USARTs */
+
+ (void)uart_register("/dev/ttyS0", &TTYS0_DEV);
+#ifdef TTYS1_DEV
+ (void)uart_register("/dev/ttyS1", &TTYS1_DEV);
+#endif
+#ifdef TTYS2_DEV
+ (void)uart_register("/dev/ttyS2", &TTYS2_DEV);
+#endif
+}
+
+/****************************************************************************
+ * Name: up_putc
+ *
+ * Description:
+ * Provide priority, low-level access to support OS debug writes
+ *
+ ****************************************************************************/
+
+int up_putc(int ch)
+{
+#ifdef HAVE_SERIAL_CONSOLE
+ struct up_dev_s *priv = (struct up_dev_s*)CONSOLE_DEV.priv;
+ uint32_t imr;
+
+ up_disableusartint(priv, &imr);
+
+ /* Check for LF */
+
+ if (ch == '\n')
+ {
+ /* Add CR */
+
+ up_lowputc('\r');
+ }
+
+ up_lowputc(ch);
+ up_restoreusartint(priv, imr);
+#endif
+ return ch;
+}
+
+#else /* CONFIG_USE_SERIALDRIVER */
+
+/****************************************************************************
+ * Name: up_putc
+ *
+ * Description:
+ * Provide priority, low-level access to support OS debug writes
+ *
+ ****************************************************************************/
+
+int up_putc(int ch)
+{
+#ifdef HAVE_SERIAL_CONSOLE
+ /* Check for LF */
+
+ if (ch == '\n')
+ {
+ /* Add CR */
+
+ up_lowputc('\r');
+ }
+
+ up_lowputc(ch);
+#endif
+ return ch;
+}
+
+#endif /* CONFIG_USE_SERIALDRIVER */
+
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_spi.h b/nuttx/arch/avr/src/at32uc3/at32uc3_spi.h
new file mode 100644
index 000000000..c2a4b99d3
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_spi.h
@@ -0,0 +1,166 @@
+/************************************************************************************
+ * arch/avr/src/at32uc3/at32uc3_spi.h
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_AVR_SRC_AT32UC3_AT32UC3_SPI_H
+#define __ARCH_AVR_SRC_AT32UC3_AT32UC3_SPI_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+
+#define AVR32_SPI_CR_OFFSET 0x000 /* Control Register */
+#define AVR32_SPI_MR_OFFSET 0x004 /* Mode Register */
+#define AVR32_SPI_RDR_OFFSET 0x008 /* Receive Data Register */
+#define AVR32_SPI_TDR_OFFSET 0x00c /* Transmit Data Register */
+#define AVR32_SPI_SR_OFFSET 0x010 /* Status Register */
+#define AVR32_SPI_IER_OFFSET 0x014 /* Interrupt Enable Register */
+#define AVR32_SPI_IDR_OFFSET 0x018 /* Interrupt Disable Register */
+#define AVR32_SPI_IMR_OFFSET 0x01c /* Interrupt Mask Register */
+#define AVR32_SPI_CSR0_OFFSET 0x030 /* Chip Select Register 0 */
+#define AVR32_SPI_CSR1_OFFSET 0x034 /* Chip Select Register 1 */
+#define AVR32_SPI_CSR2_OFFSET 0x038 /* Chip Select Register 2 */
+#define AVR32_SPI_CSR3_OFFSET 0x03c /* Chip Select Register 3 */
+#define AVR32_SPI_VERSION_OFFSET 0x0fc /* Version Register */
+
+/* Register Addresses ***************************************************************/
+
+#define AVR32_SPI0_CR (AVR32_SPI0_BASE+AVR32_SPI_CR_OFFSET)
+#define AVR32_SPI0_MR (AVR32_SPI0_BASE+AVR32_SPI_MR_OFFSET)
+#define AVR32_SPI0_RDR (AVR32_SPI0_BASE+AVR32_SPI_RDR_OFFSET)
+#define AVR32_SPI0_TDR (AVR32_SPI0_BASE+AVR32_SPI_TDR_OFFSET)
+#define AVR32_SPI0_SR (AVR32_SPI0_BASE+AVR32_SPI_SR_OFFSET)
+#define AVR32_SPI0_IER (AVR32_SPI0_BASE+AVR32_SPI_IER_OFFSET)
+#define AVR32_SPI0_IDR (AVR32_SPI0_BASE+AVR32_SPI_IDR_OFFSET)
+#define AVR32_SPI0_IMR (AVR32_SPI0_BASE+AVR32_SPI_IMR_OFFSET)
+#define AVR32_SPI0_CSR0 (AVR32_SPI0_BASE+AVR32_SPI_CSR0_OFFSET)
+#define AVR32_SPI0_CSR1 (AVR32_SPI0_BASE+AVR32_SPI_CSR1_OFFSET)
+#define AVR32_SPI0_CSR2 (AVR32_SPI0_BASE+AVR32_SPI_CSR2_OFFSET)
+#define AVR32_SPI0_CSR3 (AVR32_SPI0_BASE+AVR32_SPI_CSR3_OFFSET)
+#define AVR32_SPI0_VERSION (AVR32_SPI0_BASE+AVR32_SPI_VERSION_OFFSET)
+
+/* Register Bit-field Definitions ***************************************************/
+
+/* Control Register */
+
+#define SPI_CR_SPIEN (1 << 0) /* Bit 0: SPI Enable */
+#define SPI_CR_SPIDIS (1 << 1) /* Bit 1: SPI Disable */
+#define SPI_CR_SWRST (1 << 7) /* Bit 7: SPI Software Reset */
+#define SPI_CR_LASTXFER (1 << 24) /* Bit 24: Last Transfer */
+
+/* Mode Register */
+
+
+#define SPI_MR_MSTR (1 << 0) /* Bit 0: Master/Slave Mode */
+#define SPI_MR_PS (1 << 1) /* Bit 1: Peripheral Select */
+#define SPI_MR_PCSDEC (1 << 2) /* Bit 2: Chip Select Decode */
+#define SPI_MR_MODFDIS (1 << 4) /* Bit 4: Mode Fault Detection */
+#define SPI_MR_LLB (1 << 7) /* Bit 7: Local Loopback Enable */
+#define SPI_MR_PCS_SHIFT (16) /* Bits 16-19: Peripheral Chip Select */
+#define SPI_MR_PCS_MASK (15 << SPI_MR_PCS_SHIFT)
+#define SPI_MR_DLYBCS_SHIFT (24) /* Bits 24-31: Delay Between Chip Selects */
+#define SPI_MR_DLYBCS:_MASK (0xff << SPI_MR_DLYBCS_SHIFT)
+
+/* Receive Data Register */
+
+#define SPI_RDR_MASK (0xffff)
+
+/* Transmit Data Register */
+
+#define SPI_TDR_MASK (0xffff)
+
+/* Status Register */
+/* Interrupt Enable Register */
+/* Interrupt Disable Register */
+/* Interrupt Mask Register */
+
+#define SPI_INT_DRF (1 << 0) /* Bit 0: Receive Data Register Full */
+#define SPI_INT_TDRE (1 << 1) /* Bit 1: Transmit Data Register Empty */
+#define SPI_INT_MODF (1 << 2) /* Bit 2: Mode Fault Error */
+#define SPI_INT_OVRES (1 << 3) /* Bit 3: Overrun Error Status */
+#define SPI_INT_NSSR (1 << 8) /* Bit 8: NSS Rising */
+#define SPI_INT_TXEMPTY (1 << 9) /* Bit 9: Transmission Registers Empty */
+#define SPI_SR_SPIENS (1 << 16) /* Bit 16: SPI Enable Status (SR only) */
+
+/* Chip Select Register 0-3 */
+
+#define SPI_CSR_CPOL (1 << 0) /* Bit 0: Clock Polarity */
+#define SPI_CSR_NCPHA (1 << 1) /* Bit 1: Clock Phase */
+#define SPI_CSR_CSNAAT (1 << 2) /* Bit 2: Chip Select Not Active After Transfer */
+#define SPI_CSR_CSAAT (1 << 3) /* Bit 3: Chip Select Active After Transfer */
+#define SPI_CSR_BITS_SHIFT (4) /* Bits 4-7: Bits Per Transfer */
+#define SPI_CSR_BITS_MASK (15 << SPI_CSR_BITS_SHIFT)
+# define SPI_CSR_BITS(n) (((n)-8) << SPI_CSR_BITS_SHIFT)
+# define SPI_CSR_8BITS (0 << SPI_CSR_BITS_SHIFT)
+# define SPI_CSR_9BITS (1 << SPI_CSR_BITS_SHIFT)
+# define SPI_CSR_10BITS (2 << SPI_CSR_BITS_SHIFT)
+# define SPI_CSR_11BITS (3 << SPI_CSR_BITS_SHIFT)
+# define SPI_CSR_12BITS (4 << SPI_CSR_BITS_SHIFT)
+# define SPI_CSR_13BITS (5 << SPI_CSR_BITS_SHIFT)
+# define SPI_CSR_14BITS (6 << SPI_CSR_BITS_SHIFT)
+# define SPI_CSR_15BITS (7 << SPI_CSR_BITS_SHIFT)
+# define SPI_CSR_16BITS (8 << SPI_CSR_BITS_SHIFT)
+#define SPI_CSR_SCBR_SHIFT (8) /* Bits 8-15: Serial Clock Baud Rate */
+#define SPI_CSR_SCBR_MASK (0xff << SPI_CSR_SCBR_SHIFT)
+#define SPI_CSR_DLYBS_SHIFT (16) /* Bits 16-23: Delay Before SPCK */
+#define SPI_CSR_DLYBS_MASK (0xff << SPI_CSR_DLYBS_SHIFT)
+#define SPI_CSR_DLYBCT_SHIFT (24) /* Bits 24-31: Delay Between Consecutive Transfers */
+#define SPI_CSR_DLYBCT_MASK (0xff << SPI_CSR_DLYBCT_SHIFT)
+
+/* Version Register (Values in the Version Register vary with the version of the IP
+ * block implementation.)
+ */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_AVR_SRC_AT32UC3_AT32UC3_SPI_H */
+
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_ssc.h b/nuttx/arch/avr/src/at32uc3/at32uc3_ssc.h
new file mode 100644
index 000000000..fa67d4714
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_ssc.h
@@ -0,0 +1,267 @@
+/************************************************************************************
+ * arch/avr/src/at32uc3/at32uc3_ssc.h
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_AVR_SRC_AT32UC3_AT32UC3_SSC_H
+#define __ARCH_AVR_SRC_AT32UC3_AT32UC3_SSC_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+
+#define AVR32_SSC_CR_OFFSET 0x00 /* Control Register */
+#define AVR32_SSC_CMR_OFFSET 0x04 /* Clock Mode Register */
+#define AVR32_SSC_RCMR_OFFSET 0x10 /* Receive Clock Mode Register */
+#define AVR32_SSC_RFMR_OFFSET 0x14 /* Receive Frame Mode Register */
+#define AVR32_SSC_TCMR_OFFSET 0x18 /* Transmit Clock Mode Register */
+#define AVR32_SSC_TFMR_OFFSET 0x1c /* Transmit Frame Mode Register */
+#define AVR32_SSC_RHR_OFFSET 0x20 /* Receive Holding Register */
+#define AVR32_SSC_THR_OFFSET 0x24 /* Transmit Holding Register */
+#define AVR32_SSC_RSHR_OFFSET 0x30 /* Receive Synchronization Holding Register */
+#define AVR32_SSC_TSHR_OFFSET 0x34 /* Transmit Synchronization Holding Register */
+#define AVR32_SSC_RC0R_OFFSET 0x38 /* Receive Compare 0 Register */
+#define AVR32_SSC_RC1R_OFFSET 0x3c /* Receive Compare 1 Register */
+#define AVR32_SSC_SR_OFFSET 0x40 /* Status Register */
+#define AVR32_SSC_IER_OFFSET 0x44 /* Interrupt Enable Register */
+#define AVR32_SSC_IDR_OFFSET 0x48 /* Interrupt Disable Register */
+#define AVR32_SSC_IMR_OFFSET 0x4c /* Interrupt Mask Register */
+
+/* Register Addresses ***************************************************************/
+
+#define AVR32_SSC_CR (AVR32_SSC_BASE+AVR32_SSC_CR_OFFSET)
+#define AVR32_SSC_CMR (AVR32_SSC_BASE+AVR32_SSC_CMR_OFFSET)
+#define AVR32_SSC_RCMR (AVR32_SSC_BASE+AVR32_SSC_RCMR_OFFSET)
+#define AVR32_SSC_RFMR (AVR32_SSC_BASE+AVR32_SSC_RFMR_OFFSET)
+#define AVR32_SSC_TCMR (AVR32_SSC_BASE+AVR32_SSC_TCMR_OFFSET)
+#define AVR32_SSC_TFMR (AVR32_SSC_BASE+AVR32_SSC_TFMR_OFFSET)
+#define AVR32_SSC_RHR (AVR32_SSC_BASE+AVR32_SSC_RHR_OFFSET)
+#define AVR32_SSC_THR (AVR32_SSC_BASE+AVR32_SSC_THR_OFFSET)
+#define AVR32_SSC_RSHR (AVR32_SSC_BASE+AVR32_SSC_RSHR_OFFSET)
+#define AVR32_SSC_TSHR (AVR32_SSC_BASE+AVR32_SSC_TSHR_OFFSET)
+#define AVR32_SSC_RC0R (AVR32_SSC_BASE+AVR32_SSC_RC0R_OFFSET)
+#define AVR32_SSC_RC1R (AVR32_SSC_BASE+AVR32_SSC_RC1R_OFFSET)
+#define AVR32_SSC_SR (AVR32_SSC_BASE+AVR32_SSC_SR_OFFSET)
+#define AVR32_SSC_IER (AVR32_SSC_BASE+AVR32_SSC_IER_OFFSET)
+#define AVR32_SSC_IDR (AVR32_SSC_BASE+AVR32_SSC_IDR_OFFSET)
+#define AVR32_SSC_IMR (AVR32_SSC_BASE+AVR32_SSC_IMR_OFFSET)
+
+/* Register Bit-field Definitions ***************************************************/
+
+/* Control Register Bit-field Definitions */
+
+#define SSC_CR_RXEN (1 << 0) /* Bit 0: Receive Enable */
+#define SSC_CR_RXDIS (1 << 1) /* Bit 1: Receive Disable */
+#define SSC_CR_TXEN (1 << 8) /* Bit 8: Transmit Enable */
+#define SSC_CR_TXDIS (1 << 9) /* Bit 9: Transmit Disable */
+#define SSC_CR_SWRST (1 << 15) /* Bit 15: Software Reset */
+
+/* Clock Mode Register Bit-field Definitions */
+
+#define SSC_CMR_DIV_SHIFT (0) /* Bits 0-11: Clock Divider */
+#define SSC_CMR_DIV_MASK (0xfff << SSC_CMR_DIV_SHIFT)
+
+/* Receive Clock Mode Register Bit-field Definitions */
+
+#define SSC_RCMR_CKS_SHIFT (0) /* Bits 0-1: Receive Clock Selection */
+#define SSC_RCMR_CKS_MASK (3 << SSC_RCMR_CKS_SHIFT)
+# define SSC_RCMR_CKS_DIVCLK (0 << SSC_RCMR_CKS_SHIFT) /* Divided clock */
+# define SSC_RCMR_CKS_TXCLK (1 << SSC_RCMR_CKS_SHIFT) /* TX_CLOCK clock signal */
+# define SSC_RCMR_CKS_RXCLK (2 << SSC_RCMR_CKS_SHIFT) /* RX_CLOCK pin */
+#define SSC_RCMR_CKO_SHIFT (2) /* Bits 2-4: Receive Clock Output Mode Selection */
+#define SSC_RCMR_CKO_MASK (7 << SSC_RCMR_CKO_SHIFT)
+# define SSC_RCMR_CKO_NONE (0 << SSC_RCMR_CKO_SHIFT) /* None (Input-only) */
+# define SSC_RCMR_CKO_CONT (1 << SSC_RCMR_CKO_SHIFT) /* Continuous receive clock */
+# define SSC_RCMR_CKO_XFR (2 << SSC_RCMR_CKO_SHIFT) /* Receive clock only during data transfers */
+#define SSC_RCMR_CKI (1 << 5) /* Bit 5: Receive Clock Inversion */
+#define SSC_RCMR_CKG_SHIFT (6) /* Bits 6-7: Receive Clock Gating Selection */
+#define SSC_RCMR_CKG_MASK (3 << SSC_RCMR_CKG_SHIFT)
+# define SSC_RCMR_CKG_NONE (0 << SSC_RCMR_CKG_SHIFT) /* None, continous clock */
+# define SSC_RCMR_CKG_LOW (1 << SSC_RCMR_CKG_SHIFT) /* Enable if RX_FRAME_SYNC low */
+# define SSC_RCMR_CKG_HIGH (2 << SSC_RCMR_CKG_SHIFT) /* Enable if RX_FRAME_SYNC high */
+#define SSC_RCMR_START_SHIFT (8) /* Bits 8-11: Receive Start Selection */
+#define SSC_RCMR_START_MASK (15 << SSC_RCMR_START_SHIFT)
+# define SSC_RCMR_START_CONT (0 << SSC_RCMR_START_SHIFT) /* Continuous */
+# define SSC_RCMR_START_XMTSTART (1 << SSC_RCMR_START_SHIFT) /* Transmit start */
+# define SSC_RCMR_START_LOW (2 << SSC_RCMR_START_SHIFT) /* RX_FRAME_SYNC low */
+# define SSC_RCMR_START_HIGH (3 << SSC_RCMR_START_SHIFT) /* RX_FRAME_SYNC high */
+# define SSC_RCMR_START_FALLING (4 << SSC_RCMR_START_SHIFT) /* Falling RX_FRAME_SYNC */
+# define SSC_RCMR_START_RISING (5 << SSC_RCMR_START_SHIFT) /* Rising RX_FRAME_SYNC */
+# define SSC_RCMR_START_CHANGE (6 << SSC_RCMR_START_SHIFT) /* RX_FRAME_SYNC change */
+# define SSC_RCMR_START_BOTH (7 << SSC_RCMR_START_SHIFT) /* Any edge RX_FRAME_SYNC */
+# define SSC_RCMR_START_CMP0 (8 << SSC_RCMR_START_SHIFT) /* Compare 0 */
+#define SSC_RCMR_STOP (1 << 12) /* Bit 12: Receive Stop Selection */
+#define SSC_RCMR_STTDLY_SHIFT (16) /* Bits 16-23: Receive Start Delay */
+#define SSC_RCMR_STTDLY_MASK (0xff << SSC_RCMR_STTDLY_SHIFT)
+#define SSC_RCMR_PERIOD_SHIFT (24) /* Bits 24-31: Receive Period Divider Selection */
+#define SSC_RCMR_PERIOD_MASK (0xff << SSC_RCMR_PERIOD_SHIFT)
+
+/* Receive Frame Mode Register Bit-field Definitions */
+
+#define SSC_RFMR_DATLEN_SHIFT (0) /* Bits 0-4: Data Length */
+#define SSC_RFMR_DATLEN_MASK (0x1f << SSC_RFMR_DATLEN_SHIFT)
+#define SSC_RFMR_LOOP (1 << 5) /* Bit 5: Loop Mode */
+#define SSC_RFMR_MSBF (1 << 7) /* Bit 7: Most Significant Bit First */
+#define SSC_RFMR_DATNB_SHIFT (8) /* Bits 8-11: Data Number per Frame */
+#define SSC_RFMR_DATNB_MASK (15 << SSC_RFMR_DATNB_SHIFT)
+#define SSC_RFMR_FSLEN_SHIFT (16) /* Bits 16-19: Receive Frame Sync Length */
+#define SSC_RFMR_FSLEN_MASK (15 << SSC_RFMR_FSLEN_SHIFT)
+#define SSC_RFMR_FSOS_SHIFT (20) /* Bits 20-22: Receive Frame Sync Output Selection */
+#define SSC_RFMR_FSOS_MASK (7 << SSC_RFMR_FSOS_SHIFT)
+# define SSC_RFMR_FSOS_NONE (0 << SSC_RFMR_FSOS_SHIFT) /* None (Input-only )*/
+# define SSC_RFMR_FSOS_NEGP (1 << SSC_RFMR_FSOS_SHIFT) /* Negative Pulse */
+# define SSC_RFMR_FSOS_POSP (2 << SSC_RFMR_FSOS_SHIFT) /* Positive Pulse */
+# define SSC_RFMR_FSOS_LOW (3 << SSC_RFMR_FSOS_SHIFT) /* Driven Low during data transfer */
+# define SSC_RFMR_FSOS_HIGH (4 << SSC_RFMR_FSOS_SHIFT) /* Driven High during data transfer */
+# define SSC_RFMR_FSOS_TOGGLE (5 << SSC_RFMR_FSOS_SHIFT) /* Toggling at each start of data transfer */
+#define SSC_RFMR_FSEDGE (1 << 24) /* Bit 24: Receive Frame Sync Edge Detection */
+#define SSC_RFMR_FSLENHI_SHIFT (28) /* Bits 28-31: Receive Frame Sync Length High Part */
+#define SSC_RFMR_FSLENHI_MASK (15 << SSC_RFMR_FSLENHI_SHIFT)
+
+/* Transmit Clock Mode Register Bit-field Definitions */
+
+#define SSC_TCMR_CKS_SHIFT (0) /* Bits 0-1: Transmit Clock Selection */
+#define SSC_TCMR_CKS_MASK (3 << SSC_TCMR_CKS_SHIFT)
+# define SSC_TCMR_CKS_DIVCLK (0 << SSC_TCMR_CKS_SHIFT) /* Divided clock */
+# define SSC_TCMR_CKS_TXCLK (1 << SSC_TCMR_CKS_SHIFT) /* RX_CLOCK clock signal */
+# define SSC_TCMR_CKS_RXCLK (2 << SSC_TCMR_CKS_SHIFT) /* TX_CLOCK pin */
+#define SSC_TCMR_CKO_SHIFT (2) /* Bits 2-4: Transmit Clock Output Mode Selection */
+#define SSC_TCMR_CKO_MASK (7 << SSC_TCMR_CKO_SHIFT)
+# define SSC_TCMR_CKO_NONE (0 << SSC_TCMR_CKO_SHIFT) /* None (Input-only) */
+# define SSC_TCMR_CKO_CONT (1 << SSC_TCMR_CKO_SHIFT) /* Continuous transmit clock Output */
+# define SSC_TCMR_CKO_XFR (2 << SSC_TCMR_CKO_SHIFT) /* Transmit clock only during data transfers Output */
+#define SSC_TCMR_CKI (1 << 5) /* Bit 5: Transmit Clock Inversion */
+#define SSC_TCMR_CKG_SHIFT (6) /* Bits 6-7: Transmit Clock Gating Selection */
+#define SSC_TCMR_CKG_MASK (3 << SSC_TCMR_CKG_SHIFT)
+# define SSC_TCMR_CKG_NONE (0 << SSC_TCMR_CKG_SHIFT) /* None, continous clock */
+# define SSC_TCMR_CKG_LOW (1 << SSC_TCMR_CKG_SHIFT) /* Enable if TX_FRAME_SYNC low */
+# define SSC_TCMR_CKG_HIGH (2 << SSC_TCMR_CKG_SHIFT) /* Enable if TX_FRAME_SYNC high */
+#define SSC_TCMR_START_SHIFT (8) /* Bits 8-11: Transmit Start Selection */
+#define SSC_TCMR_START_MASK (15 << SSC_TCMR_START_SHIFT)
+# define SSC_TCMR_START_CONT (0 << SSC_TCMR_START_SHIFT) /* Continuous */
+# define SSC_TCMR_START_XMTSTART (1 << SSC_TCMR_START_SHIFT) /* Receive start */
+# define SSC_TCMR_START_LOW (2 << SSC_TCMR_START_SHIFT) /* TX_FRAME_SYNC low */
+# define SSC_TCMR_START_HIGH (3 << SSC_TCMR_START_SHIFT) /* TX_FRAME_SYNC high */
+# define SSC_TCMR_START_FALLING (4 << SSC_TCMR_START_SHIFT) /* Falling TX_FRAME_SYNC */
+# define SSC_TCMR_START_RISING (5 << SSC_TCMR_START_SHIFT) /* Rising TX_FRAME_SYNC */
+# define SSC_TCMR_START_CHANGE (6 << SSC_TCMR_START_SHIFT) /* TX_FRAME_SYNC change */
+# define SSC_TCMR_START_BOTH (7 << SSC_TCMR_START_SHIFT) /* Any edge TX_FRAME_SYNC */
+#define SSC_TCMR_STTDLY_SHIFT (16) /* Bits 16-23: Transmit Start Delay */
+#define SSC_TCMR_STTDLY_MASK (0xff << SSC_TCMR_STTDLY_SHIFT)
+#define SSC_TCMR_PERIOD_SHIFT (24) /* Bits 24-31: Transmit Period Divider Selection */
+#define SSC_TCMR_PERIOD_MASK (0xff << SSC_TCMR_PERIOD_SHIFT)
+
+/* Transmit Frame Mode Register Bit-field Definitions */
+
+#define SSC_TFMR_DATLEN_SHIFT (0) /* Bits 0-4: Data Length */
+#define SSC_TFMR_DATLEN_MASK (0x1f << SSC_TFMR_DATLEN_SHIFT)
+#define SSC_TFMR_DATDEF (1 << 5) /* Bit 5: Data Default Value */
+#define SSC_TFMR_MSBF (1 << 7) /* Bit 7: Most Significant Bit First */
+#define SSC_TFMR_DATNB_SHIFT (8) /* Bits 8-11: Data Number per Frame */
+#define SSC_TFMR_DATNB_MASK (15 << SSC_TFMR_DATNB_SHIFT)
+#define SSC_TFMR_FSLEN_SHIFT (16) /* Bits 16-19: Transmit Frame Sync Length */
+#define SSC_TFMR_FSLEN_MASK (15 << SSC_TFMR_FSLEN_SHIFT)
+#define SSC_TFMR_FSOS_SHIFT (20) /* Bits 20-22: Transmit Frame Sync Data Enable */
+#define SSC_TFMR_FSOS_MASK (7 << SSC_TFMR_FSOS_SHIFT)
+# define SSC_TFMR_FSOS_NONE (0 << SSC_TFMR_FSOS_SHIFT) /* None (Input-only )*/
+# define SSC_TFMR_FSOS_NEGP (1 << SSC_TFMR_FSOS_SHIFT) /* Negative Pulse */
+# define SSC_TFMR_FSOS_POSP (2 << SSC_TFMR_FSOS_SHIFT) /* Positive Pulse */
+# define SSC_TFMR_FSOS_LOW (3 << SSC_TFMR_FSOS_SHIFT) /* Driven Low during data transfer */
+# define SSC_TFMR_FSOS_HIGH (4 << SSC_TFMR_FSOS_SHIFT) /* Driven High during data transfer */
+# define SSC_TFMR_FSOS_TOGGLE (5 << SSC_TFMR_FSOS_SHIFT) /* Toggling at each start of data transfer */
+#define SSC_TFMR_FSDEN (1 << 23) /* Bit 23: Transmit Frame Sync Data Enable */
+#define SSC_TFMR_FSEDGE (1 << 24) /* Bit 24: Transmit Frame Sync Edge Detection */
+#define SSC_TFMR_FSLENHI_SHIFT (28) /* Bits 28-31: Transmit Frame Sync Length High Part */
+#define SSC_TFMR_FSLENHI_MASK (15 << SSC_TFMR_FSLENHI_SHIFT)
+
+/* Receive Holding Register Bit-field Definitions */
+/* Transmit Holding Register Bit-field Definitions */
+
+/* These register hold 32-bit values with no bit-fields */
+
+/* Receive Synchronization Holding Register Bit-field Definitions */
+
+#define SSC_RSHR_MASK (0xffff)
+
+/* Transmit Synchronization Holding Register Bit-field Definitions */
+
+#define SSC_TSHR_MASK (0xffff)
+
+/* Receive Compare 0 Register Bit-field Definitions */
+
+#define SSC_RC0R_MASK (0xffff)
+
+/* Receive Compare 1 Register Bit-field Definitions */
+
+#define SSC_RC1R_MASK (0xffff)
+
+/* Interrupt Enable Register Bit-field Definitions */
+/* Interrupt Disable Register Bit-field Definitions */
+/* Interrupt Mask Register Bit-field Definitions */
+
+#define SSC_INT_TXRDY (1 << 0) /* Bit 0: Transmit Ready */
+#define SSC_INT_TXEMPTY (1 << 1) /* Bit 1: Transmit Empty */
+#define SSC_INT_RXRDY (1 << 4) /* Bit 4: Receive Ready */
+#define SSC_INT_OVRUN (1 << 5) /* Bit 5: Receive Overrun */
+#define SSC_INT_CP0 (1 << 8) /* Bit 8: Compare 0 */
+#define SSC_INT_CP1 (1 << 9) /* Bit 9: Compare 1 */
+#define SSC_INT_TXSYN (1 << 10) /* Bit 10: Transmit Sync */
+#define SSC_INT_RXSYN (1 << 11) /* Bit 11: Receive Sync */
+
+/* Status Register Bit-field Definitions (Only) */
+
+#define SSC_SR_TXEN (1 << 16) /* Bit 16: Transmit Enable */
+#define SSC_SR_RXEN (1 << 17) /* Bit 17: Receive Enable */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_AVR_SRC_AT32UC3_AT32UC3_SSC_H */
+
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_tc.h b/nuttx/arch/avr/src/at32uc3/at32uc3_tc.h
new file mode 100644
index 000000000..f615d1b93
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_tc.h
@@ -0,0 +1,372 @@
+/************************************************************************************
+ * arch/avr/src/at32uc3/at32uc3_tc.h
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_AVR_SRC_AT32UC3_AT32UC3_TC_H
+#define __ARCH_AVR_SRC_AT32UC3_AT32UC3_TC_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+/* Timer Channel Offset *************************************************************/
+
+#define AVR32_TC_CHAN_OFFSET(n) ((n) << 6)
+#define AVR32_TC_CHAN0_OFFSET (0x000)
+#define AVR32_TC_CHAN1_OFFSET (0x040)
+#define AVR32_TC_CHAN2_OFFSET (0x080)
+
+/* Register offsets *****************************************************************/
+
+#define AVR32_TC_CCR_OFFSET 0x000 /* Channel Control Register */
+#define AVR32_TC_CMR_OFFSET 0x004 /* Channel Mode Register */
+#define AVR32_TC_CV_OFFSET 0x010 /* Channel Counter Value */
+#define AVR32_TC_RA_OFFSET 0x014 /* Channel Register A */
+#define AVR32_TC_RB_OFFSET 0x018 /* Channel Register B */
+#define AVR32_TC_RC_OFFSET 0x01c /* Channel Register C */
+#define AVR32_TC_SR_OFFSET 0x020 /* Channel Status Register */
+#define AVR32_TC_IER_OFFSET 0x024 /* Interrupt Enable Register */
+#define AVR32_TC_IDR_OFFSET 0x028 /* Channel Interrupt Disable Register */
+#define AVR32_TC_IMR_OFFSET 0x02c /* Channel Interrupt Mask Register */
+
+#define AVR32_TC_CCRn_OFFSET(n) (AVR32_TC_CHAN0_OFFSET(n)+AVR32_TC_CCR_OFFSET)
+#define AVR32_TC_CMRn_OFFSET(n) (AVR32_TC_CHAN0_OFFSET(n)+AVR32_TC_CMR_OFFSET)
+#define AVR32_TC_CVn_OFFSET(n) (AVR32_TC_CHAN0_OFFSET(n)+AVR32_TC_CV_OFFSET)
+#define AVR32_TC_RAn_OFFSET(n) (AVR32_TC_CHAN0_OFFSET(n)+AVR32_TC_RA_OFFSET)
+#define AVR32_TC_RBn_OFFSET(n) (AVR32_TC_CHAN0_OFFSET(n)+AVR32_TC_RB_OFFSET)
+#define AVR32_TC_RCn_OFFSET(n) (AVR32_TC_CHAN0_OFFSET(n)+AVR32_TC_RC_OFFSET)
+#define AVR32_TC_SRn_OFFSET(n) (AVR32_TC_CHAN0_OFFSET(n)+AVR32_TC_SR_OFFSET)
+#define AVR32_TC_IERn_OFFSET(n) (AVR32_TC_CHAN0_OFFSET(n)+AVR32_TC_IER_OFFSET)
+#define AVR32_TC_IDRn_OFFSET(n) (AVR32_TC_CHAN0_OFFSET(n)+AVR32_TC_IDR_OFFSET)
+#define AVR32_TC_IMRn_OFFSET(n) (AVR32_TC_CHAN0_OFFSET(n)+AVR32_TC_IMR_OFFSET)
+
+#define AVR32_TC_CCR0_OFFSET (AVR32_TC_CHAN0_OFFSET+AVR32_TC_CCR_OFFSET)
+#define AVR32_TC_CMR0_OFFSET (AVR32_TC_CHAN0_OFFSET+AVR32_TC_CMR_OFFSET)
+#define AVR32_TC_CV0_OFFSET (AVR32_TC_CHAN0_OFFSET+AVR32_TC_CV_OFFSET)
+#define AVR32_TC_RA0_OFFSET (AVR32_TC_CHAN0_OFFSET+AVR32_TC_RA_OFFSET)
+#define AVR32_TC_RB0_OFFSET (AVR32_TC_CHAN0_OFFSET+AVR32_TC_RB_OFFSET)
+#define AVR32_TC_RC0_OFFSET (AVR32_TC_CHAN0_OFFSET+AVR32_TC_RC_OFFSET)
+#define AVR32_TC_SR0_OFFSET (AVR32_TC_CHAN0_OFFSET+AVR32_TC_SR_OFFSET)
+#define AVR32_TC_IER0_OFFSET (AVR32_TC_CHAN0_OFFSET+AVR32_TC_IER_OFFSET)
+#define AVR32_TC_IDR0_OFFSET (AVR32_TC_CHAN0_OFFSET+AVR32_TC_IDR_OFFSET)
+#define AVR32_TC_IMR0_OFFSET (AVR32_TC_CHAN0_OFFSET+AVR32_TC_IMR_OFFSET)
+
+#define AVR32_TC_CCR1_OFFSET (AVR32_TC_CHAN1_OFFSET+AVR32_TC_CCR_OFFSET)
+#define AVR32_TC_CMR1_OFFSET (AVR32_TC_CHAN1_OFFSET+AVR32_TC_CMR_OFFSET)
+#define AVR32_TC_CV1_OFFSET (AVR32_TC_CHAN1_OFFSET+AVR32_TC_CV_OFFSET)
+#define AVR32_TC_RA1_OFFSET (AVR32_TC_CHAN1_OFFSET+AVR32_TC_RA_OFFSET)
+#define AVR32_TC_RB1_OFFSET (AVR32_TC_CHAN1_OFFSET+AVR32_TC_RB_OFFSET)
+#define AVR32_TC_RC1_OFFSET (AVR32_TC_CHAN1_OFFSET+AVR32_TC_RC_OFFSET)
+#define AVR32_TC_SR1_OFFSET (AVR32_TC_CHAN1_OFFSET+AVR32_TC_SR_OFFSET)
+#define AVR32_TC_IER1_OFFSET (AVR32_TC_CHAN1_OFFSET+AVR32_TC_IER_OFFSET)
+#define AVR32_TC_IDR1_OFFSET (AVR32_TC_CHAN1_OFFSET+AVR32_TC_IDR_OFFSET)
+#define AVR32_TC_IMR1_OFFSET (AVR32_TC_CHAN1_OFFSET+AVR32_TC_IMR_OFFSET)
+
+#define AVR32_TC_CCR2_OFFSET (AVR32_TC_CHAN2_OFFSET+AVR32_TC_CCR_OFFSET)
+#define AVR32_TC_CMR2_OFFSET (AVR32_TC_CHAN2_OFFSET+AVR32_TC_CMR_OFFSET)
+#define AVR32_TC_CV2_OFFSET (AVR32_TC_CHAN2_OFFSET+AVR32_TC_CV_OFFSET)
+#define AVR32_TC_RA2_OFFSET (AVR32_TC_CHAN2_OFFSET+AVR32_TC_RA_OFFSET)
+#define AVR32_TC_RB2_OFFSET (AVR32_TC_CHAN2_OFFSET+AVR32_TC_RB_OFFSET)
+#define AVR32_TC_RC2_OFFSET (AVR32_TC_CHAN2_OFFSET+AVR32_TC_RC_OFFSET)
+#define AVR32_TC_SR2_OFFSET (AVR32_TC_CHAN2_OFFSET+AVR32_TC_SR_OFFSET)
+#define AVR32_TC_IER2_OFFSET (AVR32_TC_CHAN2_OFFSET+AVR32_TC_IER_OFFSET)
+#define AVR32_TC_IDR2_OFFSET (AVR32_TC_CHAN2_OFFSET+AVR32_TC_IDR_OFFSET)
+#define AVR32_TC_IMR2_OFFSET (AVR32_TC_CHAN2_OFFSET+AVR32_TC_IMR_OFFSET)
+
+#define AVR32_TC_BCR_OFFSET 0x0c0 /* Block Control Register */
+#define AVR32_TC_BMR_OFFSET 0x0c4 /* Block Mode Register */
+
+/* Timer Channel Base Addresses *****************************************************/
+
+#define AVR32_TC_CHAN_BASE(n) (AVR32_TC_BASE+AVR32_TC_CHAN_OFFSET(n))
+#define AVR32_TC_CHAN0_BASE (AVR32_TC_BASE+AVR32_TC_CHAN0_OFFSET)
+#define AVR32_TC_CHAN1_BASE (AVR32_TC_BASE+AVR32_TC_CHAN1_OFFSET)
+#define AVR32_TC_CHAN2_BASE (AVR32_TC_BASE+AVR32_TC_CHAN2_OFFSET)
+
+/* Register Addresses ***************************************************************/
+
+#define AVR32_TC_CCR(n) (AVR32_TC_CHAN0_BASE(n)+AVR32_TC_CCR_OFFSET)
+#define AVR32_TC_CMRn(n) (AVR32_TC_CHAN0_BASE(n)+AVR32_TC_CMR_OFFSET)
+#define AVR32_TC_CV(n) (AVR32_TC_CHAN0_BASE(n)+AVR32_TC_CV_OFFSET)
+#define AVR32_TC_RA(n) (AVR32_TC_CHAN0_BASE(n)+AVR32_TC_RA_OFFSET)
+#define AVR32_TC_RB(n) (AVR32_TC_CHAN0_BASE(n)+AVR32_TC_RB_OFFSET)
+#define AVR32_TC_RC(n) (AVR32_TC_CHAN0_BASE(n)+AVR32_TC_RC_OFFSET)
+#define AVR32_TC_SR(n) (AVR32_TC_CHAN0_BASE(n)+AVR32_TC_SR_OFFSET)
+#define AVR32_TC_IER(n) (AVR32_TC_CHAN0_BASE(n)+AVR32_TC_IER_OFFSET)
+#define AVR32_TC_IDR(n) (AVR32_TC_CHAN0_BASE(n)+AVR32_TC_IDR_OFFSET)
+#define AVR32_TC_IMR(n) (AVR32_TC_CHAN0_BASE(n)+AVR32_TC_IMR_OFFSET)
+
+#define AVR32_TC_CCR0 (AVR32_TC_CHAN0_BASE+AVR32_TC_CCR_OFFSET)
+#define AVR32_TC_CMR0 (AVR32_TC_CHAN0_BASE+AVR32_TC_CMR_OFFSET)
+#define AVR32_TC_CV0 (AVR32_TC_CHAN0_BASE+AVR32_TC_CV_OFFSET)
+#define AVR32_TC_RA0 (AVR32_TC_CHAN0_BASE+AVR32_TC_RA_OFFSET)
+#define AVR32_TC_RB0 (AVR32_TC_CHAN0_BASE+AVR32_TC_RB_OFFSET)
+#define AVR32_TC_RC0 (AVR32_TC_CHAN0_BASE+AVR32_TC_RC_OFFSET)
+#define AVR32_TC_SR0 (AVR32_TC_CHAN0_BASE+AVR32_TC_SR_OFFSET)
+#define AVR32_TC_IER0 (AVR32_TC_CHAN0_BASE+AVR32_TC_IER_OFFSET)
+#define AVR32_TC_IDR0 (AVR32_TC_CHAN0_BASE+AVR32_TC_IDR_OFFSET)
+#define AVR32_TC_IMR0 (AVR32_TC_CHAN0_BASE+AVR32_TC_IMR_OFFSET)
+
+#define AVR32_TC_CCR1 (AVR32_TC_CHAN1_BASE+AVR32_TC_CCR_OFFSET)
+#define AVR32_TC_CMR1 (AVR32_TC_CHAN1_BASE+AVR32_TC_CMR_OFFSET)
+#define AVR32_TC_CV1 (AVR32_TC_CHAN1_BASE+AVR32_TC_CV_OFFSET)
+#define AVR32_TC_RA1 (AVR32_TC_CHAN1_BASE+AVR32_TC_RA_OFFSET)
+#define AVR32_TC_RB1 (AVR32_TC_CHAN1_BASE+AVR32_TC_RB_OFFSET)
+#define AVR32_TC_RC1 (AVR32_TC_CHAN1_BASE+AVR32_TC_RC_OFFSET)
+#define AVR32_TC_SR1 (AVR32_TC_CHAN1_BASE+AVR32_TC_SR_OFFSET)
+#define AVR32_TC_IER1 (AVR32_TC_CHAN1_BASE+AVR32_TC_IER_OFFSET)
+#define AVR32_TC_IDR1 (AVR32_TC_CHAN1_BASE+AVR32_TC_IDR_OFFSET)
+#define AVR32_TC_IMR1 (AVR32_TC_CHAN1_BASE+AVR32_TC_IMR_OFFSET)
+
+#define AVR32_TC_CCR2 (AVR32_TC_CHAN2_BASE+AVR32_TC_CCR_OFFSET)
+#define AVR32_TC_CMR2 (AVR32_TC_CHAN2_BASE+AVR32_TC_CMR_OFFSET)
+#define AVR32_TC_CV2 (AVR32_TC_CHAN2_BASE+AVR32_TC_CV_OFFSET)
+#define AVR32_TC_RA2 (AVR32_TC_CHAN2_BASE+AVR32_TC_RA_OFFSET)
+#define AVR32_TC_RB2 (AVR32_TC_CHAN2_BASE+AVR32_TC_RB_OFFSET)
+#define AVR32_TC_RC2 (AVR32_TC_CHAN2_BASE+AVR32_TC_RC_OFFSET)
+#define AVR32_TC_SR2 (AVR32_TC_CHAN2_BASE+AVR32_TC_SR_OFFSET)
+#define AVR32_TC_IER2 (AVR32_TC_CHAN2_BASE+AVR32_TC_IER_OFFSET)
+#define AVR32_TC_IDR2 (AVR32_TC_CHAN2_BASE+AVR32_TC_IDR_OFFSET)
+#define AVR32_TC_IMR2 (AVR32_TC_CHAN2_BASE+AVR32_TC_IMR_OFFSET)
+
+#define AVR32_TC_BCR (AVR32_TC_BASE+AVR32_TC_BCR_OFFSET)
+#define AVR32_TC_BMR (AVR32_TC_BASE+AVR32_TC_BMR_OFFSET)
+
+/* Register Bit-field Definitions ***************************************************/
+
+/* Channel Control Register */
+
+#define TC_CCR_CLKEN (1 << 0) /* Bit 0: Counter Clock Enable Command */
+#define TC_CCR_CLKDIS (1 << 1) /* Bit 3: Counter Clock Disable Command */
+#define TC_CCR_SWTRG (1 << 2) /* Bit 2: Software Trigger Command */
+
+/* Channel Mode Register -- All Modes */
+
+#define TC_CMR_TCCLKS_SHIFT (0) /* Bits 0-2: Clock Selection */
+#define TC_CMR_TCCLKS_MASK (7 << TC_CMR_TCCLKS_SHIFT)
+# define TC_CMR_TCCLKS_TMRCLK1 (0 << TC_CMR_TCCLKS_SHIFT) /* TIMER_CLOCK1 */
+# define TC_CMR_TCCLKS_TMRCLK2 (1 << TC_CMR_TCCLKS_SHIFT) /* TIMER_CLOCK2 */
+# define TC_CMR_TCCLKS_TMRCLK3 (2 << TC_CMR_TCCLKS_SHIFT) /* TIMER_CLOCK3 */
+# define TC_CMR_TCCLKS_TMRCLK4 (3 << TC_CMR_TCCLKS_SHIFT) /* TIMER_CLOCK4 */
+# define TC_CMR_TCCLKS_TMRCLK5 (4 << TC_CMR_TCCLKS_SHIFT) /* TIMER_CLOCK5 */
+# define TC_CMR_TCCLKS_XC0 (5 << TC_CMR_TCCLKS_SHIFT) /* XC0 */
+# define TC_CMR_TCCLKS_XC1 (6 << TC_CMR_TCCLKS_SHIFT) /* XC1 */
+# define TC_CMR_TCCLKS_XC2 (7 << TC_CMR_TCCLKS_SHIFT) /* XC2 */
+#define TC_CMR_CLKI (1 << 3) /* Bit 3: Clock Invert */
+#define TC_CMR_BURST_SHIFT (4) /* Bits 4-5: Burst Signal Selection */
+#define TC_CMR_BURST_MASK (3 << TC_CMR_BURST_SHIFT)
+# define TC_CMR_BURST_NONE (0 << TC_CMR_BURST_SHIFT) /* Clock not gated by External signal */
+# define TC_CMR_BURST_XC0 (1 << TC_CMR_BURST_SHIFT) /* XC0 ANDed with selected clock */
+# define TC_CMR_BURST_XC1 (2 << TC_CMR_BURST_SHIFT) /* XC1 ANDed with selected clock */
+# define TC_CMR_BURST_XC2 (3 << TC_CMR_BURST_SHIFT) /* XC2 ANDed with selected clock */
+
+#define TC_CMR_WAVE (1 << 15) /* Bit 15: Enable waveform mode */
+
+/* Channel Mode Register -- Capture Mode */
+
+#define TC_CMR_LDBSTOP (1 << 6) /* Bit 6: Counter Clock Stopped with RB Loading */
+#define TC_CMR_LDBDIS (1 << 7) /* Bit 7: Counter Clock Disable with RB Loading */
+#define TC_CMR_ETRGEDG_SHIFT (8) /* Bits 8-9: External Trigger Edge Selection */
+#define TC_CMR_ETRGEDG_MASK (3 << TC_CMR_ETRGEDG_SHIFT)
+# define TC_CMR_ETRGEDG_NONE (0 << TC_CMR_ETRGEDG_SHIFT) /* None */
+# define TC_CMR_ETRGEDG_RISING (1 << TC_CMR_ETRGEDG_SHIFT) /* Rising edge */
+# define TC_CMR_ETRGEDG_FALLING (2 << TC_CMR_ETRGEDG_SHIFT) /* Falling edge */
+# define TC_CMR_ETRGEDG_BOTH (3 << TC_CMR_ETRGEDG_SHIFT) /* Each edge */
+#define TC_CMR_ABETRG (1 << 10) /* Bit 10: TIOA or TIOB External Trigger Selection */
+#define TC_CMR_CPCTRG (1 << 14) /* Bit 14: RC Compare Trigger Enable */
+#define TC_CMR_LDRA_SHIFT (16) /* Bits 16-17: A Loading Selection */
+#define TC_CMR_LDRA_MASK (3 << TC_CMR_LDRA_SHIFT)
+# define TC_CMR_LDRA_NONE (0 << TC_CMR_LDRA_SHIFT) /* None */
+# define TC_CMR_LDRA_RISING (1 << TC_CMR_LDRA_SHIFT) /* Rising edge of TIOA */
+# define TC_CMR_LDRA_FALLING (2 << TC_CMR_LDRA_SHIFT) /* Falling edge of TIOA */
+# define TC_CMR_LDRA_BOTH (3 << TC_CMR_LDRA_SHIFT) /* Each edge of TIOA */
+#define TC_CMR_LDRB_SHIFT (18) /* Bits 18-19: RB Loading Selection */
+#define TC_CMR_LDRB_MASK (3 << TC_CMR_LDRB_SHIFT)
+# define TC_CMR_LDRB_NONE (0 << TC_CMR_LDRB_SHIFT) /* None */
+# define TC_CMR_LDRB_RISING (1 << TC_CMR_LDRB_SHIFT) /* Rising edge of TIOA */
+# define TC_CMR_LDRB_FALLING (2 << TC_CMR_LDRB_SHIFT) /* Falling edge of TIOA */
+# define TC_CMR_LDRB_BOTH (3 << TC_CMR_LDRB_SHIFT) /* Each edge of TIOA */
+
+/* Channel Mode Register -- Waveform Mode */
+
+#define TC_CMR_CPCSTOP (1 << 6) /* Bit 6: Counter Clock Stopped with RC Compare */
+#define TC_CMR_CPCDIS (1 << 7) /* Bit 7: Counter Clock Disable with RC Compare */
+#define TC_CMR_EEVTEDG_SHIFT (8) /* Bits 8-9: External Event Edge Selection */
+#define TC_CMR_EEVTEDG_MASK (3 << TC_CMR_EEVTEDG_SHIFT)
+# define TC_CMR_EEVTEDG_NONE (0 << TC_CMR_EEVTEDG_SHIFT) /* None */
+# define TC_CMR_EEVTEDG_RISING (1 << TC_CMR_EEVTEDG_SHIFT) /* Rising edge */
+# define TC_CMR_EEVTEDG_FALLING (2 << TC_CMR_EEVTEDG_SHIFT) /* Falling edge */
+# define TC_CMR_EEVTEDG_BOTH (3 << TC_CMR_EEVTEDG_SHIFT) /* Each edge */
+#define TC_CMR_EEVT_SHIFT (10) /* Bits 10-11: External Event Selection */
+#define TC_CMR_EEVT_MASK (3 << TC_CMR_EEVT_SHIFT)
+# define TC_CMR_EEVT_TIOB (0 << TC_CMR_EEVT_SHIFT) /* TIOB Input */
+# define TC_CMR_EEVT_XC0 (1 << TC_CMR_EEVT_SHIFT) /* XC0 Output */
+# define TC_CMR_EEVT_XC1 (2 << TC_CMR_EEVT_SHIFT) /* XC1 Output */
+# define TC_CMR_EEVT_XC2 (3 << TC_CMR_EEVT_SHIFT) /* XC2 Output */
+#define TC_CMR_ENETRG (1 << 12) /* Bit 12: External Event Trigger Enable */
+#define TC_CMR_WAVSEL_SHIFT (13) /* Bits 13-14: Waveform Selection */
+#define TC_CMR_WAVSEL_MASK (3 << TC_CMR_WAVSEL_SHIFT)
+# define TC_CMR_WAVSEL_UPNOT (0 << TC_CMR_WAVSEL_SHIFT) /* UP mode no trigger on RC compare */
+# define TC_CMR_WAVSEL_UPDWNNOT (1 << TC_CMR_WAVSEL_SHIFT) /* UPDOWN mode no trigger on RC compare */
+# define TC_CMR_WAVSEL_UPT (2 << TC_CMR_WAVSEL_SHIFT) /* UP mode with trigger on RC compare */
+# define TC_CMR_WAVSEL_UPDWNT (3 << TC_CMR_WAVSEL_SHIFT) /* UPDOWN mode with trigger on RC compare */
+#define TC_CMR_ACPA_SHIFT (16) /* Bits 16-17: RA Compare Effect on TIOA */
+#define TC_CMR_ACPA_MASK (3 << TC_CMR_ACPA_SHIFT)
+# define TC_CMR_ACPA_NONE (0 << TC_CMR_ACPA_SHIFT)
+# define TC_CMR_ACPA_SET (1 << TC_CMR_ACPA_SHIFT)
+# define TC_CMR_ACPA_CLEAR (2 << TC_CMR_ACPA_SHIFT)
+# define TC_CMR_ACPA_TOGGLE (3 << TC_CMR_ACPA_SHIFT)
+#define TC_CMR_ACPC_SHIFT (18) /* Bits 18-19: RC Compare Effect on TIOA */
+#define TC_CMR_ACPC_MASK (3 << TC_CMR_ACPC_SHIFT)
+# define TC_CMR_ACPC_NONE (0 << TC_CMR_ACPC_SHIFT)
+# define TC_CMR_ACPC_SET (1 << TC_CMR_ACPC_SHIFT)
+# define TC_CMR_ACPC_CLEAR (2 << TC_CMR_ACPC_SHIFT)
+# define TC_CMR_ACPC_TOGGLE (3 << TC_CMR_ACPC_SHIFT)
+#define TC_CMR_AEEVT_SHIFT (20) /* Bits 20-21: External Event Effect on TIOA */
+#define TC_CMR_AEEVT_MASK (3 << TC_CMR_AEEVT_SHIFT)
+# define TC_CMR_AEEVT_NONE (0 << TC_CMR_AEEVT_SHIFT)
+# define TC_CMR_AEEVT_SET (1 << TC_CMR_AEEVT_SHIFT)
+# define TC_CMR_AEEVT_CLEAR (2 << TC_CMR_AEEVT_SHIFT)
+# define TC_CMR_AEEVT_TOGGLE (3 << TC_CMR_AEEVT_SHIFT)
+#define TC_CMR_ASWTRG_SHIFT (22) /* Bits 22-23: Software Trigger Effect on TIOA */
+#define TC_CMR_ASWTRG_MASK (3 << TC_CMR_ASWTRG_SHIFT)
+# define TC_CMR_ASWTRG_NONE (0 << TC_CMR_ASWTRG_SHIFT)
+# define TC_CMR_ASWTRG_SET (1 << TC_CMR_ASWTRG_SHIFT)
+# define TC_CMR_ASWTRG_CLEAR (2 << TC_CMR_ASWTRG_SHIFT)
+# define TC_CMR_ASWTRG_TOGGLE (3 << TC_CMR_ASWTRG_SHIFT)
+#define TC_CMR_BCPB_SHIFT (24) /* Bits 24-25: RB Compare Effect on TIOB */
+#define TC_CMR_BCPB_MASK (3 << TC_CMR_BCPB_SHIFT)
+# define TC_CMR_BCPB_NONE (0 << TC_CMR_BCPB_SHIFT)
+# define TC_CMR_BCPB_SET (1 << TC_CMR_BCPB_SHIFT)
+# define TC_CMR_BCPB_CLEAR (2 << TC_CMR_BCPB_SHIFT)
+# define TC_CMR_BCPB_TOGGLE (3 << TC_CMR_BCPB_SHIFT)
+#define TC_CMR_BCPC_SHIFT (26) /* Bits 26-27: RC Compare Effect on TIOB */
+#define TC_CMR_BCPC_MASK (3 << TC_CMR_BCPC_SHIFT)
+# define TC_CMR_BCPC_NONE (0 << TC_CMR_BCPC_SHIFT)
+# define TC_CMR_BCPC_SET (1 << TC_CMR_BCPC_SHIFT)
+# define TC_CMR_BCPC_CLEAR (2 << TC_CMR_BCPC_SHIFT)
+# define TC_CMR_BCPC_TOGGLE (3 << TC_CMR_BCPC_SHIFT)
+#define TC_CMR_BEEVT_SHIFT (28) /* Bits 28-29: External Event Effect on TIOB */
+#define TC_CMR_BEEVT_MASK (3 << TC_CMR_BEEVT_SHIFT)
+# define TC_CMR_BEEVT_NONE (0 << TC_CMR_BEEVT_SHIFT)
+# define TC_CMR_BEEVT_SET (1 << TC_CMR_BEEVT_SHIFT)
+# define TC_CMR_BEEVT_CLEAR (2 << TC_CMR_BEEVT_SHIFT)
+# define TC_CMR_BEEVT_TOGGLE (3 << TC_CMR_BEEVT_SHIFT)
+#define TC_CMR_BSWTRG_SHIFT (30) /* Bits 30-31: Software Trigger Effect on TIOB */
+#define TC_CMR_BSWTRG_MASK (3 << TC_CMR_BSWTRG_SHIFT)
+# define TC_CMR_BSWTRG_NONE (0 << TC_CMR_BSWTRG_SHIFT)
+# define TC_CMR_BSWTRG_SET (1 << TC_CMR_BSWTRG_SHIFT)
+# define TC_CMR_BSWTRG_CLEAR (2 << TC_CMR_BSWTRG_SHIFT)
+# define TC_CMR_BSWTRG_TOGGLE (3 << TC_CMR_BSWTRG_SHIFT)
+
+/* Channel Counter Value */
+
+#define TC_CV_MASK (0xffff)
+
+/* Channel Register A */
+
+#define TC_RA_MASK (0xffff)
+
+/* Channel Register B */
+
+#define TC_RB_MASK (0xffff)
+
+/* Channel Register C */
+
+#define TC_RC_MASK (0xffff)
+
+/* Channel Status Register (common) */
+/* Interrupt Enable Register */
+/* Channel Interrupt Disable Register */
+/* Channel Interrupt Mask Register */
+
+#define TC_INT_COVFS (1 << 0) /* Bit 0: Counter Overflow Status/Int */
+#define TC_INT_LOVRS (1 << 1) /* Bit 1: Load Overrun Status/Int */
+#define TC_INT_CPAS (1 << 2) /* Bit 2: RA Compare Status/Int */
+#define TC_INT_CPBS (1 << 3) /* Bit 3: RB Compare Status/Int */
+#define TC_INT_CPCS (1 << 4) /* Bit 4: RC Compare Status/Int */
+#define TC_INT_LDRAS (1 << 5) /* Bit 5: RA Loading Status/Int */
+#define TC_INT_LDRBS (1 << 6) /* Bit 6: RB Loading Status/Int */
+#define TC_INT_ETRGS (1 << 7) /* Bit 7: External Trigger Status/Int */
+
+/* Channel Status Register (only) */
+
+#define TC_SR_CLKSTA (1 << 16) /* Bit 16: Clock Enabling Status */
+#define TC_SR_MTIOA (1 << 17) /* Bit 17: TIOA Mirror */
+#define TC_SR_MTIOB (1 << 18) /* Bit 18: TIOB Mirror */
+
+/* Block Control Register */
+
+#define TC_BCR_SYNC (1 << 0) /* Bit 0: Synchro Command */
+
+/* Block Mode Register */
+
+#define TC_BMR_TC0XC0S_SHIFT (0) /* Bits 0-1: External Clock Signal 0 Selection */
+#define TC_BMR_TC0XC0S_MASK (3 << TC_BMR_TC0XC0S_SHIFT)
+# define TC_BMR_TC2XC0S_TCLK0 (0 << TC_BMR_TC2XC0S_SHIFT) /* TCLK0 */
+# define TC_BMR_TC2XC0S_NONE (1 << TC_BMR_TC2XC0S_SHIFT) /* None */
+# define TC_BMR_TC2XC0S_TIOA1 (2 << TC_BMR_TC2XC0S_SHIFT) /* TIOA1 */
+# define TC_BMR_TC2XC0S_TIOA2 (3 << TC_BMR_TC2XC0S_SHIFT) /* TIOA2 */
+#define TC_BMR_TC1XC1S_SHIFT (2) /* Bits 2-3: External Clock Signal 1 Selection */
+#define TC_BMR_TC1XC1S_MASK (3 << TC_BMR_TC1XC1S_SHIFT)
+# define TC_BMR_TC2XC1S_TCLK1 (0 << TC_BMR_TC2XC1S_SHIFT) /* TCLK1 */
+# define TC_BMR_TC2XC1S_NONE (1 << TC_BMR_TC2XC1S_SHIFT) /* None */
+# define TC_BMR_TC2XC1S_TIOA0 (2 << TC_BMR_TC2XC1S_SHIFT) /* TIOA0 */
+# define TC_BMR_TC2XC1S_TIOA2 (3 << TC_BMR_TC2XC1S_SHIFT) /* TIOA2 */
+#define TC_BMR_TC2XC2S_SHIFT (3) /* Bits 4-5: External Clock Signal 2 Selection */
+#define TC_BMR_TC2XC2S_MASK (3 << TC_BMR_TC2XC2S_SHIFT)
+# define TC_BMR_TC2XC2S_TCLK2 (0 << TC_BMR_TC2XC2S_SHIFT) /* TCLK2 */
+# define TC_BMR_TC2XC2S_NONE (1 << TC_BMR_TC2XC2S_SHIFT) /* None */
+# define TC_BMR_TC2XC2S_TIOA0 (2 << TC_BMR_TC2XC2S_SHIFT) /* TIOA0 */
+# define TC_BMR_TC2XC2S_TIOA1 (3 << TC_BMR_TC2XC2S_SHIFT) /* TIOA1 */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_AVR_SRC_AT32UC3_AT32UC3_TC_H */
+
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_timerisr.c b/nuttx/arch/avr/src/at32uc3/at32uc3_timerisr.c
new file mode 100644
index 000000000..7630f03d0
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_timerisr.c
@@ -0,0 +1,190 @@
+/****************************************************************************
+ * arch/avr/src/at32uc3/at32uc3_timerisr.c
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <debug.h>
+#include <nuttx/arch.h>
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+
+#include "chip.h"
+#include "at32uc3_internal.h"
+#include "at32uc3_rtc.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* The desired timer interrupt frequency is normally provided by the
+ * definition CLK_TCK (see include/time.h). CLK_TCK defines the desired
+ * number of system clock ticks per second. That value is a user configurable
+ * setting that defaults to 100 (100 ticks per second = 10 MS interval).
+ *
+ * However, the AVR RTC does not support that default value well and so, we
+ * will insist that default is over-ridden by CONFIG_TICKS_PER_MSEC in the
+ * configuration file. Further, we will insist that CONFIG_TICKS_PER_MSEC
+ * have the value 8 (see reasoning below).
+ */
+
+#if defined(CONFIG_MSEC_PER_TICK) && CONFIG_MSEC_PER_TICK != 10
+# error "Only a 100KHz system clock is supported"
+#endif
+
+/* The frequency of the RTC is given by:
+ *
+ * fRTC = fINPUT / 2**(PSEL + 1)
+ *
+ * Using the 32KHz clock, various RTC counting can be obtained:
+ *
+ * fRTC = 32000 / 2**16 = 32000/65536 = 0.49Hz -> 2048 ms per tick
+ * fRTC = 32000 / 2**15 = 32000/32768 = 0.98Hz -> 1024 ms per tick
+ * fRTC = 32000 / 2**14 = 32000/16384 = 1.95Hz -> 512 ms per tick
+ * fRTC = 32000 / 2**13 = 32000/8192 = 3.9Hz -> 256 ms per tick
+ * fRTC = 32000 / 2**12 = 32000/4096 = 7.8Hz -> 128 ms per tick
+ * fRTC = 32000 / 2**11 = 32000/2048 = 15.6Hz -> 64 ms per tick
+ * fRTC = 32000 / 2**10 = 32000/1024 = 31.3Hz -> 32 ms per tick
+ * fRTC = 32000 / 2**9 = 32000/512 = 62.5Hz -> 16 ms per tick
+ * fRTC = 32000 / 2**8 = 32000/256 = 125Hz -> 8 ms per tick
+ * fRTC = 32000 / 2**7 = 32000/128 = 250Hz -> 4 ms per tick
+ * fRTC = 32000 / 2**6 = 32000/64 = 500Hz -> 2 ms per tick
+ * fRTC = 32000 / 2**5 = 32000/32 = 1KHz -> 1 ms per tick
+ * fRTC = 32000 / 2**4 = 32000/16 = 2KHz -> 500 us per tick
+ * fRTC = 32000 / 2**3 = 32000/8 = 4KHz -> 250 us per tick
+ * fRTC = 32000 / 2**2 = 32000/4 = 8KHz -> 125 us per tick
+ * fRTC = 32000 / 2 = 16KHz -> 62.5 us per tick
+ *
+ * We'll use PSEL == 1 (fRTC == 125ns) and we will set TOP to 79.
+ * Therefore, the TOP interrupt should occur after 79+1=80 counts
+ * at a rate of 125us x 80 = 10 ms
+ */
+
+#define AV32_PSEL 15
+#define AV32_TOP (80-1)
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: rtc_busy
+ *
+ * Description:
+ * Make sure that the RTC is no busy before trying to operate on it. If
+ * the RTC is busy, it will discard writes to TOP, VAL, and CTRL.
+ *
+ ****************************************************************************/
+
+static void rtc_waitnotbusy(void)
+{
+ while ((getreg32(AVR32_RTC_CTRL) & RTC_CTRL_BUSY) == 0);
+}
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: up_timerisr
+ *
+ * Description:
+ * The timer ISR will perform a variety of services for various portions
+ * of the systems.
+ *
+ ****************************************************************************/
+
+int up_timerisr(int irq, uint32_t *regs)
+{
+ /* Clear the pending timer interrupt */
+
+ putreg32(RTC_INT_TOPI, AVR32_RTC_ICR);
+
+ /* Process timer interrupt */
+
+ sched_process_timer();
+ return 0;
+}
+
+/****************************************************************************
+ * Function: up_timerinit
+ *
+ * Description:
+ * This function is called during start-up to initialize the timer
+ * interrupt. NOTE: This function depends on setup of OSC32 by
+ * up_clkinitialize().
+ *
+ ****************************************************************************/
+
+void up_timerinit(void)
+{
+ uint32_t regval;
+
+ /* Configure the RTC. Source == 32KHz OSC32 */
+
+ rtc_waitnotbusy();
+ putreg32((RTC_CTRL_CLK32 | (AV32_PSEL << RTC_CTRL_PSEL_SHIFT) | RTC_CTRL_CLKEN),
+ AVR32_RTC_CTRL);
+
+ /* Set the counter value to zero and the TOP value to AVR32_TOP (see above) */
+
+ rtc_waitnotbusy();
+ putreg32(0, AVR32_RTC_VAL);
+ putreg32(AV32_TOP, AVR32_RTC_TOP);
+
+ /* Attach the timer interrupt vector */
+
+ (void)irq_attach(AVR32_IRQ_RTC, (xcpt_t)up_timerisr);
+
+ /* Enable RTC interrupts */
+
+ putreg32(RTC_INT_TOPI, AVR32_RTC_IER);
+
+ /* Enable the RTC */
+
+ rtc_waitnotbusy();
+ regval = getreg32(AVR32_RTC_CTRL);
+ regval |= RTC_CTRL_EN;
+ putreg32(regval, AVR32_RTC_CTRL);
+}
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_twi.h b/nuttx/arch/avr/src/at32uc3/at32uc3_twi.h
new file mode 100644
index 000000000..afec99fb1
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_twi.h
@@ -0,0 +1,161 @@
+/************************************************************************************
+ * arch/avr/src/at32uc3/at32uc3_twi.h
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_AVR_SRC_AT32UC3_AT32UC3_TWI_H
+#define __ARCH_AVR_SRC_AT32UC3_AT32UC3_TWI_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+
+#define AVR32_TWI_CR_OFFSET 0x00 /* Control Register */
+#define AVR32_TWI_MMR_OFFSET 0x04 /* Master Mode Register */
+#define AVR32_TWI_SMR_OFFSET 0x08 /* Slave Mode Register */
+#define AVR32_TWI_IADR_OFFSET 0x0c /* Internal Address Register */
+#define AVR32_TWI_CWGR_OFFSET 0x10 /* Clock Waveform Generator Register */
+#define AVR32_TWI_SR_OFFSET 0x20 /* Status Register */
+#define AVR32_TWI_IER_OFFSET 0x24 /* Interrupt Enable Register */
+#define AVR32_TWI_IDR_OFFSET 0x28 /* Interrupt Disable Register */
+#define AVR32_TWI_IMR_OFFSET 0x2c /* Interrupt Mask Register */
+#define AVR32_TWI_RHR_OFFSET 0x30 /* Receive Holding Register */
+#define AVR32_TWI_THR_OFFSET 0x34 /* Transmit Holding Register */
+
+/* Register Addresses ***************************************************************/
+
+#define AVR32_TWI_CR (AVR32_TWI_BASE+AVR32_TWI_CR_OFFSET)
+#define AVR32_TWI_MMR (AVR32_TWI_BASE+AVR32_TWI_MMR_OFFSET)
+#define AVR32_TWI_SMR (AVR32_TWI_BASE+AVR32_TWI_SMR_OFFSET)
+#define AVR32_TWI_IADR (AVR32_TWI_BASE+AVR32_TWI_IADR_OFFSET)
+#define AVR32_TWI_CWGR (AVR32_TWI_BASE+AVR32_TWI_CWGR_OFFSET)
+#define AVR32_TWI_SR (AVR32_TWI_BASE+AVR32_TWI_SR_OFFSET)
+#define AVR32_TWI_IER (AVR32_TWI_BASE+AVR32_TWI_IER_OFFSET)
+#define AVR32_TWI_IDR (AVR32_TWI_BASE+AVR32_TWI_IDR_OFFSET)
+#define AVR32_TWI_IMR (AVR32_TWI_BASE+AVR32_TWI_IMR_OFFSET)
+#define AVR32_TWI_RHR (AVR32_TWI_BASE+AVR32_TWI_RHR_OFFSET)
+#define AVR32_TWI_THR (AVR32_TWI_BASE+AVR32_TWI_THR_OFFSET)
+
+/* Register Bit-field Definitions ***************************************************/
+
+/* Control Register Bit-field Definitions */
+
+#define TWI_CR_START (1 << 0) /* Bit 0: Send a START Condition */
+#define TWI_CR_STOP (1 << 1) /* Bit 1: Send a STOP Condition */
+#define TWI_CR_MSEN (1 << 2) /* Bit 2: TWI Master Mode Enabled */
+#define TWI_CR_MSDIS (1 << 3) /* Bit 3: TWI Master Mode Disabled */
+#define TWI_CR_SVEN (1 << 4) /* Bit 4: TWI Slave Mode Enabled */
+#define TWI_CR_SVDIS (1 << 5) /* Bit 5: TWI Slave Mode Disabled */
+#define TWI_CR_SWRST (1 << 7) /* Bit 6: Software Reset */
+
+/* Master Mode Register Bit-field Definitions */
+
+#define TWI_MMR_IADRSZ_SHIFT (8) /* Bits 8-9: Internal Device Address Size */
+#define TWI_MMR_IADRSZ_MASK (3 << TWI_MMR_IADRSZ_SHIFT)
+# define TWI_MMR_IADRSZ_ NONE (0 << TWI_MMR_IADRSZ_SHIFT) /* No internal device address */
+# define TWI_MMR_IADRSZ_1BYTE (1 << TWI_MMR_IADRSZ_SHIFT) /* One-byte internal device address */
+# define TWI_MMR_IADRSZ_2BYTES (2 << TWI_MMR_IADRSZ_SHIFT) /* Two-byte internal device address */
+# define TWI_MMR_IADRSZ_3BYTES (3 << TWI_MMR_IADRSZ_SHIFT) /* Three-byte internal device address */
+#define TWI_MMR_MREAD (1 << 12) /* Bit 12: Master Read Direction */
+#define TWI_MMR_DADR_SHIFT (16) /* Bits 16-22: Device Address */
+#define TWI_MMR_DADR:_MASK (0x7f << TWI_MMR_DADR_SHIFT)
+
+/* Slave Mode Register Bit-field Definitions */
+
+#define TWI_SMR_SADR_SHIFT (16) /* Bits 16-22: Slave Address */
+#define TWI_SMR_SADR_MASK (0x7f << TWI_SMR_SADR_SHIFT)
+
+/* Internal Address Register Bit-field Definitions */
+
+#define TWI_IADR_MASK (0x00ffffff)
+
+/* Clock Waveform Generator Register Bit-field Definitions */
+
+#define TWI_CWGR_CLDIV_SHIFT (0) /* Bits 0-7: Clock Low Divider */
+#define TWI_CWGR_CLDIV_MASK (0xff <<TWI_CWGR_CLDIV_SHIFT)
+#define TWI_CWGR_CHDIV_SHIFT (8) /* Bits 8-15: Clock High Divider */
+#define TWI_CWGR_CHDIV_MASK (0xff << TWI_CWGR_CHDIV_SHIFT)
+#define TWI_CWGR_CKDIV_SHIFT (16) /* Bits 16-18: Clock Divider */
+#define TWI_CWGR_CKDIV:_MASK (7 << TWI_CWGR_CKDIV_SHIFT)
+
+/* Status Register Bit-field Definitions */
+/* Interrupt Enable Register Bit-field Definitions */
+/* Interrupt Disable Register Bit-field Definitions */
+/* Interrupt Mask Register Bit-field Definitions */
+
+#define TWI_INT_TXCOMP (1 << 0) /* Bit 0: Transmission Completed (automatically set / reset) */
+#define TWI_INT_RXRDY (1 << 1) /* Bit 1: Receive Holding Register Ready (automatically set / reset) */
+#define TWI_INT_TXRDY (1 << 2) /* Bit 2: Transmit Holding Register Ready (automatically set / reset) */
+#define TWI_SR_SVREAD (1 << 3) /* Bit 3: Slave Read (automatically set / reset) */
+#define TWI_INT_SVACC (1 << 4) /* Bit 4: Slave Access (automatically set / reset) */
+#define TWI_INT_GACC (1 << 5) /* Bit 5: General Call Access (clear on read) */
+#define TWI_INT_OVRE (1 << 6) /* Bit 6: Overrun Error (clear on read) */
+#define TWI_INT_NACK (1 << 8) /* Bit 8: Not Acknowledged (clear on read) */
+#define TWI_INT_ARBLST (1 << 9) /* Bit 9: Arbitration Lost (clear on read) */
+#define TWI_INT_SCLWS (1 << 10) /* Bit 10: Clock Wait State (automatically set / reset) */
+#define TWI_INT_EOSACC (1 << 11) /* Bit 11: End Of Slave Access (clear on read) */
+#define TWI_INT_ENDRX (1 << 12) /* Bit 12: End of RX buffer */
+#define TWI_INT_ENDTX (1 << 13) /* Bit 13: End of TX buffer */
+#define TWI_INT_RXBUFF (1 << 14) /* Bit 14: RX Buffer Full */
+#define TWI_INT_TXBUFE (1 << 15) /* Bit 15: TX Buffer Empty */
+
+/* Receive Holding Register Bit-field Definitions */
+
+#define TWI_RHR_MASK (0xff)
+
+/* Transmit Holding Register Bit-field Definitions */
+
+#define TWI_THR_MASK (0xff)
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_AVR_SRC_AT32UC3_AT32UC3_TWI_H */
+
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_usart.h b/nuttx/arch/avr/src/at32uc3/at32uc3_usart.h
new file mode 100644
index 000000000..350946321
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_usart.h
@@ -0,0 +1,339 @@
+/************************************************************************************
+ * arch/avr/src/at32uc3/at32uc3_usart.h
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_AVR_SRC_AT32UC3_AT32UC3_USART_H
+#define __ARCH_AVR_SRC_AT32UC3_AT32UC3_USART_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+
+#define AVR32_USART_CR_OFFSET 0x0000 /* Control Register */
+#define AVR32_USART_MR_OFFSET 0x0004 /* Mode Register */
+#define AVR32_USART_IER_OFFSET 0x0008 /* Interrupt Enable Register */
+#define AVR32_USART_IDR_OFFSET 0x000c /* Interrupt Disable Register */
+#define AVR32_USART_IMR_OFFSET 0x0010 /* Interrupt Mask Register */
+#define AVR32_USART_CSR_OFFSET 0x0014 /* Channel Status Register */
+#define AVR32_USART_RHR_OFFSET 0x0018 /* Receiver Holding Register */
+#define AVR32_USART_THR_OFFSET 0x001c /* Transmitter Holding Register */
+#define AVR32_USART_BRGR_OFFSET 0x0020 /* Baud Rate Generator Register */
+#define AVR32_USART_RTOR_OFFSET 0x0024 /* Receiver Time-out Register */
+#define AVR32_USART_TTGR_OFFSET 0x0028 /* Transmitter Timeguard Register */
+#define AVR32_USART_FIDI_OFFSET 0x0040 /* FI DI Ratio Register */
+#define AVR32_USART_NER_OFFSET 0x0044 /* Number of Errors Register */
+#define AVR32_USART_IFR_OFFSET 0x004c /* IrDA Filter Register */
+#define AVR32_USART_MAN_OFFSET 0x0050 /* Manchester Encoder Decoder Register */
+#define AVR32_USART_VERSION_OFFSET 0x00fc /* Version Register */
+
+/* Register Addresses ***************************************************************/
+
+#define AVR32_USART0_CR (AVR32_USART0_BASE+AVR32_USART_CR_OFFSET)
+#define AVR32_USART0_MR (AVR32_USART0_BASE+AVR32_USART_MR_OFFSET)
+#define AVR32_USART0_IER (AVR32_USART0_BASE+AVR32_USART_IER_OFFSET)
+#define AVR32_USART0_IDR (AVR32_USART0_BASE+AVR32_USART_IDR_OFFSET)
+#define AVR32_USART0_IMR (AVR32_USART0_BASE+AVR32_USART_IMR_OFFSET)
+#define AVR32_USART0_CSR (AVR32_USART0_BASE+AVR32_USART_CSR_OFFSET)
+#define AVR32_USART0_RHR (AVR32_USART0_BASE+AVR32_USART_RHR_OFFSET)
+#define AVR32_USART0_THR (AVR32_USART0_BASE+AVR32_USART_THR_OFFSET)
+#define AVR32_USART0_BRGR (AVR32_USART0_BASE+AVR32_USART_BRGR_OFFSET)
+#define AVR32_USART0_RTOR (AVR32_USART0_BASE+AVR32_USART_RTOR_OFFSET)
+#define AVR32_USART0_TTGR (AVR32_USART0_BASE+AVR32_USART_TTGR_OFFSET)
+#define AVR32_USART0_FIDI (AVR32_USART0_BASE+AVR32_USART_FIDI_OFFSET)
+#define AVR32_USART0_NER (AVR32_USART0_BASE+AVR32_USART_NER_OFFSET)
+#define AVR32_USART0_IFR (AVR32_USART0_BASE+AVR32_USART_IFR_OFFSET)
+#define AVR32_USART0_MAN (AVR32_USART0_BASE+AVR32_USART_MAN_OFFSET)
+#define AVR32_USART0_VERSION (AVR32_USART0_BASE+AVR32_USART_VERSION_OFFSET)
+
+#define AVR32_USART1_CR (AVR32_USART1_BASE+AVR32_USART_CR_OFFSET)
+#define AVR32_USART1_MR (AVR32_USART1_BASE+AVR32_USART_MR_OFFSET)
+#define AVR32_USART1_IER (AVR32_USART1_BASE+AVR32_USART_IER_OFFSET)
+#define AVR32_USART1_IDR (AVR32_USART1_BASE+AVR32_USART_IDR_OFFSET)
+#define AVR32_USART1_IMR (AVR32_USART1_BASE+AVR32_USART_IMR_OFFSET)
+#define AVR32_USART1_CSR (AVR32_USART1_BASE+AVR32_USART_CSR_OFFSET)
+#define AVR32_USART1_RHR (AVR32_USART1_BASE+AVR32_USART_RHR_OFFSET)
+#define AVR32_USART1_THR (AVR32_USART1_BASE+AVR32_USART_THR_OFFSET)
+#define AVR32_USART1_BRGR (AVR32_USART1_BASE+AVR32_USART_BRGR_OFFSET)
+#define AVR32_USART1_RTOR (AVR32_USART1_BASE+AVR32_USART_RTOR_OFFSET)
+#define AVR32_USART1_TTGR (AVR32_USART1_BASE+AVR32_USART_TTGR_OFFSET)
+#define AVR32_USART1_FIDI (AVR32_USART1_BASE+AVR32_USART_FIDI_OFFSET)
+#define AVR32_USART1_NER (AVR32_USART1_BASE+AVR32_USART_NER_OFFSET)
+#define AVR32_USART1_IFR (AVR32_USART1_BASE+AVR32_USART_IFR_OFFSET)
+#define AVR32_USART1_MAN (AVR32_USART1_BASE+AVR32_USART_MAN_OFFSET)
+#define AVR32_USART1_VERSION (AVR32_USART1_BASE+AVR32_USART_VERSION_OFFSET)
+
+#define AVR32_USART2_CR (AVR32_USART2_BASE+AVR32_USART_CR_OFFSET)
+#define AVR32_USART2_MR (AVR32_USART2_BASE+AVR32_USART_MR_OFFSET)
+#define AVR32_USART2_IER (AVR32_USART2_BASE+AVR32_USART_IER_OFFSET)
+#define AVR32_USART2_IDR (AVR32_USART2_BASE+AVR32_USART_IDR_OFFSET)
+#define AVR32_USART2_IMR (AVR32_USART2_BASE+AVR32_USART_IMR_OFFSET)
+#define AVR32_USART2_CSR (AVR32_USART2_BASE+AVR32_USART_CSR_OFFSET)
+#define AVR32_USART2_RHR (AVR32_USART2_BASE+AVR32_USART_RHR_OFFSET)
+#define AVR32_USART2_THR (AVR32_USART2_BASE+AVR32_USART_THR_OFFSET)
+#define AVR32_USART2_BRGR (AVR32_USART2_BASE+AVR32_USART_BRGR_OFFSET)
+#define AVR32_USART2_RTOR (AVR32_USART2_BASE+AVR32_USART_RTOR_OFFSET)
+#define AVR32_USART2_TTGR (AVR32_USART2_BASE+AVR32_USART_TTGR_OFFSET)
+#define AVR32_USART2_FIDI (AVR32_USART2_BASE+AVR32_USART_FIDI_OFFSET)
+#define AVR32_USART2_NER (AVR32_USART2_BASE+AVR32_USART_NER_OFFSET)
+#define AVR32_USART2_IFR (AVR32_USART2_BASE+AVR32_USART_IFR_OFFSET)
+#define AVR32_USART2_MAN (AVR32_USART2_BASE+AVR32_USART_MAN_OFFSET)
+#define AVR32_USART2_VERSION (AVR32_USART2_BASE+AVR32_USART_VERSION_OFFSET)
+
+/* Register Bit-field Definitions ***************************************************/
+
+/* CR Register Bit-field Definitions */
+
+#define USART_CR_RSTRX (1 << 2) /* Bit 2: Reset Receiver */
+#define USART_CR_RSTTX (1 << 3) /* Bit 3: Reset Transmitter */
+#define USART_CR_RXEN (1 << 4) /* Bit 4: Receiver Enable */
+#define USART_CR_RXDIS (1 << 5) /* Bit 5: Receiver Disable */
+#define USART_CR_TXEN (1 << 6) /* Bit 6: Transmitter Enable */
+#define USART_CR_TXDIS (1 << 7) /* Bit 7: Transmitter Disable */
+#define USART_CR_RSTSTA (1 << 8) /* Bit 8: Reset Status Bits */
+#define USART_CR_STTBRK (1 << 9) /* Bit 9: Start Break */
+#define USART_CR_STPBRK (1 << 10) /* Bit 10: Stop Break */
+#define USART_CR_STTTO (1 << 11) /* Bit 11: Start Time-out */
+#define USART_CR_SENDA (1 << 12) /* Bit 12: Send Address */
+#define USART_CR_RSTIT (1 << 13) /* Bit 13: Reset Iterations */
+#define USART_CR_RSTNACK (1 << 14) /* Bit 14: Reset Non Acknowledge */
+#define USART_CR_RETTO (1 << 15) /* Bit 15: Rearm Time-out */
+#define USART_CR_DTREN (1 << 16) /* Bit 16: Data Terminal Ready Enable */
+#define USART_CR_DTRDIS (1 << 17) /* Bit 17: Data Terminal Ready Disable */
+#define USART_CR_RTSEN (1 << 18) /* Bit 18: Request to Send Enable */
+#define USART_CR_FCS (1 << 18) /* Bit 18: Force SPI Chip Select */
+#define USART_CR_RTSDIS (1 << 19) /* Bit 19: Request to Send Disable */
+#define USART_CR_RCS (1 << 19) /* Bit 19: Release SPI Chip Select */
+
+/* MR Register Bit-field Definitions */
+
+#define USART_MR_MODE_SHIFT (0)
+#define USART_MR_MODE_MASK (15 << USART_MR_MODE_SHIFT)
+# define USART_MR_MODE_NORMAL (0 << USART_MR_MODE_SHIFT) /* Normal */
+# define USART_MR_MODE_RS485 (1 << USART_MR_MODE_SHIFT) /* RS485 */
+# define USART_MR_MODE_HW (2 << USART_MR_MODE_SHIFT) /* Hardware Handshaking */
+# define USART_MR_MODE_MODEM (3 << USART_MR_MODE_SHIFT) /* Modem */
+# define USART_MR_MODE_T0 (4 << USART_MR_MODE_SHIFT) /* IS07816 Protocol: T = 0 */
+# define USART_MR_MODE_T1 (6 << USART_MR_MODE_SHIFT) /* IS07816 Protocol: T = 1 */
+# define USART_MR_MODE_IRDA (8 << USART_MR_MODE_SHIFT) /* IrDA */
+# define USART_MR_MODE_MASTER (14 << USART_MR_MODE_SHIFT) /* SPI Master */
+# define USART_MR_MODE_SLAVE (15 << USART_MR_MODE_SHIFT) /* SPI Slave */
+#define USART_MR_USCLKS_SHIFT (4) /* Bits 4-5: Clock Selection */
+#define USART_MR_USCLKS_MASK (3 << USART_MR_USCLKS_SHIFT)
+# define USART_MR_USCLKS_CLKUSART (0 << USART_MR_USCLKS_SHIFT) /* CLK_USART */
+# define USART_MR_USCLKS_DIV (1 << USART_MR_USCLKS_SHIFT) /* CLK_USART/DIV */
+# define USART_MR_USCLKS_CLK (3 << USART_MR_USCLKS_SHIFT) /* CLK */
+#define USART_MR_CHRL_SHIFT (6) /* Bit 6-7: Character Length */
+#define USART_MR_CHRL_MASK (3 << USART_MR_CHRL_SHIFT)
+# define USART_MR_CHRL_BITS(n) (((n) - 5) << USART_MR_CHRL_SHIFT)
+# define USART_MR_CHRL_5BITS (0 << USART_MR_CHRL_SHIFT) /* 5 bits */
+# define USART_MR_CHRL_6BITS (1 << USART_MR_CHRL_SHIFT) /* 6 bits */
+# define USART_MR_CHRL_7BITS (2 << USART_MR_CHRL_SHIFT) /* 7 bits */
+# define USART_MR_CHRL_8BITS (3 << USART_MR_CHRL_SHIFT) /* 8 bits */
+#define USART_MR_SYNC (1 << 8) /* Bit 8: Synchronous Mode Select */
+#define USART_MR_CPHA (1 << 8) /* Bit 8: SPI Clock Phase */
+#define USART_MR_PAR_SHIFT (9) /* Bits 9-11: Parity Type */
+#define USART_MR_PAR_MASK (7 << USART_MR_PAR_SHIFT)
+# define USART_MR_PAR_EVEN (0 << USART_MR_PAR_SHIFT) /* Even parity */
+# define USART_MR_PAR_ODD (1 << USART_MR_PAR_SHIFT) /* Odd parity */
+# define USART_MR_PAR_SPACE (2 << USART_MR_PAR_SHIFT) /* Parity forced to 0 (Space) */
+# define USART_MR_PAR_MARK (3 << USART_MR_PAR_SHIFT) /* Parity forced to 1 (Mark) */
+# define USART_MR_PAR_NONE (4 << USART_MR_PAR_SHIFT) /* No parity */
+# define USART_MR_PAR_MULTIDROP (6 << USART_MR_PAR_SHIFT) /* Multidrop mode */
+#define USART_MR_NBSTOP_SHIFT (12) /* Bits 12-13: Number of Stop Bits */
+#define USART_MR_NBSTOP_MASK (3 << USART_MR_NBSTOP_SHIFT)
+# define USART_MR_NBSTOP_1 (0 << USART_MR_NBSTOP_SHIFT) /* 1 stop bit */
+# define USART_MR_NBSTOP_1p5 (1 << USART_MR_NBSTOP_SHIFT) /* 1.5 stop bits */
+# define USART_MR_NBSTOP_2 (2 << USART_MR_NBSTOP_SHIFT) /* 2 stop bits */
+#define USART_MR_CHMODE_SHIFT (14) /* Bits 14-15: Channel Mode */
+#define USART_MR_CHMODE_MASK (3 << USART_MR_CHMODE_SHIFT)
+# define USART_MR_CHMODE_NORMAL (0 << USART_MR_CHMODE_SHIFT) /* Normal Mode */
+# define USART_MR_CHMODE_AUTO (1 << USART_MR_CHMODE_SHIFT) /* Automatic Echo */
+# define USART_MR_CHMODE_LLPBK (2 << USART_MR_CHMODE_SHIFT) /* Local Loopback */
+# define USART_MR_CHMODE_RLPBK (3 << USART_MR_CHMODE_SHIFT) /* Remote Loopback */
+#define USART_MR_MSBF (1 << 16) /* Bit 16: Bit Order */
+#define USART_MR_CPOL (1 << 16) /* Bit 16: SPI Clock Polarity */
+#define USART_MR_MODE9 (1 << 17) /* Bit 17: 9-bit Character Length */
+#define USART_MR_CLKO (1 << 18) /* Bit 18: Clock Output Select */
+#define USART_MR_OVER (1 << 19) /* Bit 19: Oversampling Mode */
+#define USART_MR_INACK (1 << 20) /* Bit 20: Inhibit Non Acknowledge */
+#define USART_MR_DSNACK (1 << 21) /* Bit 21: Disable Successive NACK */
+#define USART_MR_VAR_SYNC (1 << 22) /* Bit 22: Variable Synchronization */
+#define USART_MR_MAXITER_SHIFT (24) /* Bits 24-26: Maximum iterations */
+#define USART_MR_MAXITER_MASK (7 << USART_MR_MAXITER_SHIFT)
+#define USART_MR_FILTER (1 << 28) /* Bit 28: Infrared Receive Line Filter */
+#define USART_MR_MAN (1 << 29) /* Bit 29: Manchester Encoder/Decoder Enable */
+#define USART_MR_MODSYNC (1 << 30) /* Bit 30: Manchester Synchronization Mode */
+#define USART_MR_ONEBIT (1 << 31) /* Bit 31: Start Frame Delimiter Selector */
+
+/* IER, IDR, and IMR (and CSR) Register Bit-field Definitions */
+
+#define USART_INT_RXRDY (1 << 0) /* Bit 0: */
+#define USART_INT_TXRDY (1 << 1) /* Bit 1: */
+#define USART_INT_RXBRK (1 << 2) /* Bit 2: */
+#define USART_INT_OVRE (1 << 5) /* Bit 5: */
+#define USART_INT_FRAME (1 << 6) /* Bit 6: */
+#define USART_INT_PARE (1 << 7) /* Bit 7: */
+#define USART_INT_TIMEOUT (1 << 8) /* Bit 8: */
+#define USART_INT_TXEMPTY (1 << 9) /* Bit 9: */
+#define USART_INT_ITER (1 << 10) /* Bit 10: */
+#define USART_INT_UNRE (1 << 10) /* Bit 10: */
+#define USART_INT_RXBUFF (1 << 12) /* Bit 12: */
+#define USART_INT_NACK (1 << 13) /* Bit 13: */
+#define USART_INT_RIIC (1 << 16) /* Bit 16: */
+#define USART_INT_DSRIC (1 << 17) /* Bit 17: */
+#define USART_INT_DCDIC (1 << 18) /* Bit 18: */
+#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 */
+
+#define USART_CSR_RXRDY (1 << 0) /* Bit 0: */
+#define USART_CSR_TXRDY (1 << 1) /* Bit 1: */
+#define USART_CSR_RXBRK (1 << 2) /* Bit 2: */
+#define USART_CSR_OVRE (1 << 5) /* Bit 5: */
+#define USART_CSR_FRAME (1 << 6) /* Bit 6: */
+#define USART_CSR_PARE (1 << 7) /* Bit 7: */
+#define USART_CSR_TIMEOUT (1 << 8) /* Bit 8: */
+#define USART_CSR_TXEMPTY (1 << 9) /* Bit 9: */
+#define USART_CSR_ITER (1 << 10) /* Bit 10: */
+#define USART_CSR_UNRE (1 << 10) /* Bit 10: */
+#define USART_CSR_RXBUFF (1 << 12) /* Bit 12: */
+#define USART_CSR_NACK (1 << 13) /* Bit 13: */
+#define USART_CSR_RIIC (1 << 16) /* Bit 16: */
+#define USART_CSR_DSRIC (1 << 17) /* Bit 17: */
+#define USART_CSR_DCDIC (1 << 18) /* Bit 18: */
+#define USART_CSR_CTSIC (1 << 19) /* Bit 19: */
+#define USART_CSR_RI (1 << 20) /* Bit 20: */
+#define USART_CSR_DSR (1 << 21) /* Bit 21: Image of DSR Input */
+#define USART_CSR_DCD (1 << 22) /* Bit 22: Image of DCD Input*/
+#define USART_CSR_CTS (1 << 23) /* Bit 23: Image of CTS Input */
+#define USART_CSR_MANERR (1 << 24) /* Bit 24: Manchester Error */
+
+/* RHR Register Bit-field Definitions */
+
+#define USART_RHR_RXCHR_SHIFT (0) /* Bits 0-8: Received Character */
+#define USART_RHR_RXCHR_MASK (0x1ff << USART_RHR_RXCHR_SHIFT)
+#define USART_RHR_RXSYNH (1 << 15) /* Bit 15: Received Sync */
+
+/* THR Register Bit-field Definitions */
+
+#define USART_THR_TXCHR_SHIFT (0) /* Bits 0-8: Character to be Transmitted */
+#define USART_THR_TXCHR_MASK (0x1ff << USART_RHR_RXCHR_SHIFT)
+#define USART_THR_TXSYNH (1 << 15) /* Bit 15: Sync Field to be transmitted */
+
+/* BRGR Register Bit-field Definitions */
+
+#define USART_BRGR_CD_SHIFT (0) /* Bits 0-15: Clock Divider */
+#define USART_BRGR_CD_MASK (0xffff << USART_BRGR_CD_SHIFT)
+#define USART_BRGR_FP_SHIFT (16) /* Bits 16-18: Fractional Part */
+#define USART_BRGR_FP_MASK (7 << USART_BRGR_FP_SHIFT)
+
+/* RTOR Register Bit-field Definitions */
+
+#define USART_RTOR_SHIFT (0) /* Bits0-15: Time-out Value */
+#define USART_RTOR_MASK (0xffff << USART_RTOR_SHIFT)
+
+/* TTGR Register Bit-field Definitions */
+
+#define USART_TTGR_SHIFT (0) /* Bits 0-7: Timeguard Value */
+#define USART_TTGR_MASK (0xff << USART_TTGR_SHIFT)
+
+/* FIDI Register Bit-field Definitions */
+
+#define USART_FIDI_SHIFT (0) /* Bits 0-10: FI Over DI Ratio Value */
+#define USART_FIDI_MASK (0x7ff<< USART_FIDI_SHIFT)
+
+/* NER Register Bit-field Definitions */
+
+#define USART_NER_SHIFT (0) /* Bits 0-7: Number of Errors */
+#define USART_NER_MASK (0xff << USART_NER_SHIFT)
+
+/* IFR Register Bit-field Definitions */
+
+#define USART_IFR_SHIFT (0) /* Bits 0-7: IrDA Filter */
+#define USART_IFR_MASK (0xff << USART_IFR_SHIFT)
+
+/* MAN Register Bit-field Definitions */
+
+#define USART_MAN_TXPL_SHIFT (0) /* Bits 0-3: Transmitter Preamble Length */
+#define USART_MAN_TXPL_MASK (15 << USART_MAN_TXPL_SHIFT)
+#define USART_MAN_TXPP_SHIFT (8) /* Bits 8-9: Transmitter Preamble Pattern */
+#define USART_MAN_TXPP_MASK (3 << USART_MAN_TXPP_SHIFT)
+# define USART_MAN_TXPP_ALLONE (0 << USART_MAN_TXPP_SHIFT) /* ALL_ONE */
+# define USART_MAN_TXPP_ALLZERO (1 << USART_MAN_TXPP_SHIFT) /* ALL_ZERO */
+# define USART_MAN_TXPP_ZER0ONE (2 << USART_MAN_TXPP_SHIFT) /* ZERO_ONE */
+# define USART_MAN_TXPP_ONEZERO (3 << USART_MAN_TXPP_SHIFT) /* ONE_ZERO */
+#define USART_MAN_TXMPOL (1 << 12) /* Bit 12: Transmitter Manchester Polarity */
+#define USART_MAN_RXPL_SHIFT (16) /* Bits 16-19: Receiver Preamble Length */
+#define USART_MAN_RXPL_MASK (15 << USART_MAN_RXPL_SHIFT)
+#define USART_MAN_RXPP_SHIFT (24) /* Bits 24-25: Receiver Preamble Pattern detected */
+#define USART_MAN_RXPP_MASK (3 << USART_MAN_RXPP_SHIFT)
+# define USART_MAN_RXPP_ALLONE (0 << USART_MAN_TXPP_SHIFT) /* ALL_ONE */
+# define USART_MAN_RXPP_ALLZERO (1 << USART_MAN_TXPP_SHIFT) /* ALL_ZERO */
+# define USART_MAN_RXPP_ZER0ONE (2 << USART_MAN_TXPP_SHIFT) /* ZERO_ONE */
+# define USART_MAN_RXPP_ONEZERO (3 << USART_MAN_TXPP_SHIFT) /* ONE_ZERO */
+#define USART_MAN_RXMPOL (1 << 28) /* Bit 28: Receiver Manchester Polarity */
+#define USART_MAN_DRIFT (1 << 30) /* Bit 30: Drift compensation */
+
+/* VERSION Register Bit-field Definitions */
+
+#define USART_VERSION_SHIFT (0) /* Bits 0-12: Version of the module */
+#define USART_VERSION_MASK (0xfff << USART_VERSION_SHIFT)
+#define USART_VARIANT_SHIFT (16) /* Bits 16-19: (Reserved) */
+#define USART_VARIANT_MASK (15 << USART_VARIANT_SHIFT)
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_AVR_SRC_AT32UC3_AT32UC3_USART_H */
+
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_usbb.h b/nuttx/arch/avr/src/at32uc3/at32uc3_usbb.h
new file mode 100644
index 000000000..b6bc1765a
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_usbb.h
@@ -0,0 +1,1098 @@
+/************************************************************************************
+ * arch/avr/src/at32uc3/at32uc3_usbb.h
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_AVR_SRC_AT32UC3_AT32UC3_USBB_H
+#define __ARCH_AVR_SRC_AT32UC3_AT32UC3_USBB_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+
+/* USB Device Registers */
+
+#define AVR32_USBB_UDCON_OFFSET 0x0000 /* Device General Control Register */
+#define AVR32_USBB_UDINT_OFFSET 0x0004 /* Device Global Interrupt Register */
+#define AVR32_USBB_UDINTCLR_OFFSET 0x0008 /* Device Global Interrupt Clear Register */
+#define AVR32_USBB_UDINTSET_OFFSET 0x000c /* Device Global Interrupt Set Register */
+#define AVR32_USBB_UDINTE_OFFSET 0x0010 /* Device Global Interrupt Enable Register */
+#define AVR32_USBB_UDINTECLR_OFFSET 0x0014 /* Device Global Interrupt Enable Clear Register */
+#define AVR32_USBB_UDINTESET_OFFSET 0x0018 /* Device Global Interrupt Enable Set Register */
+#define AVR32_USBB_UERST_OFFSET 0x001c /* Endpoint Enable/Reset Register */
+#define AVR32_USBB_UDFNUM_OFFSET 0x0020 /* Device Frame Number Register */
+
+#define AVR32_USBB_UECFG_OFFSET(n) (0x0100+((n)<<2))
+#define AVR32_USBB_UECFG0_OFFSET 0x0100 /* Endpoint 0 Configuration Register */
+#define AVR32_USBB_UECFG1_OFFSET 0x0104 /* Endpoint 1 Configuration Register */
+#define AVR32_USBB_UECFG2_OFFSET 0x0108 /* Endpoint 2 Configuration Register */
+#define AVR32_USBB_UECFG3_OFFSET 0x010c /* Endpoint 3 Configuration Register */
+#define AVR32_USBB_UECFG4_OFFSET 0x0110 /* Endpoint 4 Configuration Register */
+#define AVR32_USBB_UECFG5_OFFSET 0x0114 /* Endpoint 5 Configuration Register */
+#define AVR32_USBB_UECFG6_OFFSET 0x0118 /* Endpoint 6 Configuration Register */
+
+#define AVR32_USBB_UESTA_OFFSET(n) (0x0130+((n)<<2))
+#define AVR32_USBB_UESTA0_OFFSET 0x0130 /* Endpoint 0 Status Register */
+#define AVR32_USBB_UESTA1_OFFSET 0x0134 /* Endpoint 1 Status Register */
+#define AVR32_USBB_UESTA2_OFFSET 0x0138 /* Endpoint 2 Status Register */
+#define AVR32_USBB_UESTA3_OFFSET 0x013c /* Endpoint 3 Status Register */
+#define AVR32_USBB_UESTA4_OFFSET 0x0140 /* Endpoint 4 Status Register */
+#define AVR32_USBB_UESTA5_OFFSET 0x0144 /* Endpoint 5 Status Register */
+#define AVR32_USBB_UESTA6_OFFSET 0x0148 /* Endpoint 6 Status Register */
+
+#define AVR32_USBB_UESTACLR_OFFSET(n) (0x0160+((n)<<2))
+#define AVR32_USBB_UESTA0CLR_OFFSET 0x0160 /* Endpoint 0 Status Clear Register */
+#define AVR32_USBB_UESTA1CLR_OFFSET 0x0164 /* Endpoint 1 Status Clear Register */
+#define AVR32_USBB_UESTA2CLR_OFFSET 0x0168 /* Endpoint 2 Status Clear Register */
+#define AVR32_USBB_UESTA3CLR_OFFSET 0x016c /* Endpoint 3 Status Clear Register */
+#define AVR32_USBB_UESTA4CLR_OFFSET 0x0170 /* Endpoint 4 Status Clear Register */
+#define AVR32_USBB_UESTA5CLR_OFFSET 0x0174 /* Endpoint 5 Status Clear Register */
+#define AVR32_USBB_UESTA6CLR_OFFSET 0x0178 /* Endpoint 6 Status Clear Register */
+
+#define AVR32_USBB_UESTASET_OFFSET(n) (0x0190+((n)<<2))
+#define AVR32_USBB_UESTA0SET_OFFSET 0x0190 /* Endpoint 0 Status Set Register */
+#define AVR32_USBB_UESTA1SET_OFFSET 0x0194 /* Endpoint 1 Status Set Register */
+#define AVR32_USBB_UESTA2SET_OFFSET 0x0198 /* Endpoint 2 Status Set Register */
+#define AVR32_USBB_UESTA3SET_OFFSET 0x019c /* Endpoint 3 Status Set Register */
+#define AVR32_USBB_UESTA4SET_OFFSET 0x01a0 /* Endpoint 4 Status Set Register */
+#define AVR32_USBB_UESTA5SET_OFFSET 0x01a4 /* Endpoint 5 Status Set Register */
+#define AVR32_USBB_UESTA6SET_OFFSET 0x01a8 /* Endpoint 6 Status Set Register */
+
+#define AVR32_USBB_UECON_OFFSET(n) (0x01c0+((n)<<2))
+#define AVR32_USBB_UECON0_OFFSET 0x01c0 /* Endpoint 0 Control Register */
+#define AVR32_USBB_UECON1_OFFSET 0x01c4 /* Endpoint 1 Control Register */
+#define AVR32_USBB_UECON2_OFFSET 0x01c8 /* Endpoint 2 Control Register */
+#define AVR32_USBB_UECON3_OFFSET 0x01cc /* Endpoint 3 Control Register */
+#define AVR32_USBB_UECON4_OFFSET 0x01d0 /* Endpoint 4 Control Register */
+#define AVR32_USBB_UECON5_OFFSET 0x01d4 /* Endpoint 5 Control Register */
+#define AVR32_USBB_UECON6_OFFSET 0x01d8 /* Endpoint 7 Control Register */
+
+#define AVR32_USBB_UECONSET_OFFSET(n) (0x01f0+((n)<<2))
+#define AVR32_USBB_UECON0SET_OFFSET 0x01f0 /* Endpoint 0 Control Set Register */
+#define AVR32_USBB_UECON1SET_OFFSET 0x01f4 /* Endpoint 1 Control Set Register */
+#define AVR32_USBB_UECON2SET_OFFSET 0x01f8 /* Endpoint 2 Control Set Register */
+#define AVR32_USBB_UECON3SET_OFFSET 0x01fc /* Endpoint 3 Control Set Register */
+#define AVR32_USBB_UECON4SET_OFFSET 0x0200 /* Endpoint 4 Control Set Register */
+#define AVR32_USBB_UECON5SET_OFFSET 0x0204 /* Endpoint 5 Control Set Register */
+#define AVR32_USBB_UECON6SET_OFFSET 0x0208 /* Endpoint 6 Control Set Register */
+
+#define AVR32_USBB_UECONCLR_OFFSET(n) (0x0220+((n)<<2))
+#define AVR32_USBB_UECON0CLR_OFFSET 0x0220 /* Endpoint 0 Control Clear Register */
+#define AVR32_USBB_UECON1CLR_OFFSET 0x0224 /* Endpoint 1 Control Clear Register */
+#define AVR32_USBB_UECON2CLR_OFFSET 0x0228 /* Endpoint 2 Control Clear Register */
+#define AVR32_USBB_UECON3CLR_OFFSET 0x022c /* Endpoint 3 Control Clear Register */
+#define AVR32_USBB_UECON4CLR_OFFSET 0x0230 /* Endpoint 4 Control Clear Register */
+#define AVR32_USBB_UECON5CLR_OFFSET 0x0234 /* Endpoint 5 Control Clear Register */
+#define AVR32_USBB_UECON6CLR_OFFSET 0x0238 /* Endpoint 6 Control Clear Register */
+
+#define AVR32_UDDMA_OFFSET(n) (0x0300+((n)<<4))
+#define AVR32_UDDMA_NEXTDESC_OFFSET 0x0000 /* Device DMA Channel Next Descriptor Address Register */
+#define AVR32_UDDMA_ADDR_OFFSET 0x0004 /* Device DMA Channel HSB Address Register */
+#define AVR32_UDDMA_CTRL_OFFSET 0x0008 /* Device DMA Channel Control Register */
+#define AVR32_UDDMA_STATUS_OFFSET 0x000c /* Device DMA Channel Status Register */
+
+#define AVR32_UDDMA1_NEXTDESC_OFFSET 0x0310 /* Device DMA Channel 1 Next Descriptor Address Register */
+#define AVR32_UDDMA1_ADDR_OFFSET 0x0314 /* Device DMA Channel 1 HSB Address Register */
+#define AVR32_UDDMA1_CTRL_OFFSET 0x0318 /* Device DMA Channel 1 Control Register */
+#define AVR32_UDDMA1_STATUS_OFFSET 0x031c /* Device DMA Channel 1 Status Register */
+
+#define AVR32_UDDMA1_NEXTDESC_OFFSET 0x0310 /* Device DMA Channel 1 Next Descriptor Address Register */
+#define AVR32_UDDMA1_ADDR_OFFSET 0x0314 /* Device DMA Channel 1 HSB Address Register */
+#define AVR32_UDDMA1_CTRL_OFFSET 0x0318 /* Device DMA Channel 1 Control Register */
+#define AVR32_UDDMA1_STATUS_OFFSET 0x031c /* Device DMA Channel 1 Status Register */
+
+#define AVR32_UDDMA2_NEXTDESC_OFFSET 0x0320 /* Device DMA Channel 2 Next Descriptor Address Register */
+#define AVR32_UDDMA2_ADDR_OFFSET 0x0324 /* Device DMA Channel 2 HSB Address Register */
+#define AVR32_UDDMA2_CTRL_OFFSET 0x0328 /* Device DMA Channel 2 Control Register */
+#define AVR32_UDDMA2_STATUS_OFFSET 0x032c /* Device DMA Channel 2 Status Register */
+
+#define AVR32_UDDMA3_NEXTDESC_OFFSET 0x0330 /* Device DMA Channel 3 Next Descriptor Address Register */
+#define AVR32_UDDMA3_ADDR_OFFSET 0x0334 /* Device DMA Channel 3 HSB Address Register */
+#define AVR32_UDDMA3_CTRL_OFFSET 0x0338 /* Device DMA Channel 3 Control Register */
+#define AVR32_UDDMA3_STATUS_OFFSET 0x033c /* Device DMA Channel 3 Status Register */
+
+#define AVR32_UDDMA4_NEXTDESC_OFFSET 0x0340 /* Device DMA Channel 4 Next Descriptor Address Register */
+#define AVR32_UDDMA4_ADDR_OFFSET 0x0344 /* Device DMA Channel 4 HSB Address Register */
+#define AVR32_UDDMA4_CTRL_OFFSET 0x0348 /* Device DMA Channel 4 Control Register */
+#define AVR32_UDDMA4_STATUS_OFFSET 0x034c /* Device DMA Channel 4 Status Register */
+
+#define AVR32_UDDMA5_NEXTDESC_OFFSET 0x0350 /* Device DMA Channel 5 Next Descriptor Address Register */
+#define AVR32_UDDMA5_ADDR_OFFSET 0x0354 /* Device DMA Channel 5 HSB Address Register */
+#define AVR32_UDDMA5_CTRL_OFFSET 0x0358 /* Device DMA Channel 5 Control Register */
+#define AVR32_UDDMA5_STATUS_OFFSET 0x035c /* Device DMA Channel 5 Status Register */
+
+#define AVR32_UDDMA6_NEXTDESC_OFFSET 0x0360 /* Device DMA Channel 6 Next Descriptor Address Register */
+#define AVR32_UDDMA6_ADDR_OFFSET 0x0364 /* Device DMA Channel 6 HSB Address Register */
+#define AVR32_UDDMA6_CTRL_OFFSET 0x0368 /* Device DMA Channel 6 Control Register */
+#define AVR32_UDDMA6_STATUS_OFFSET 0x036c /* Device DMA Channel 6 Status Register */
+
+/* USB Host Registers */
+
+#define AVR32_USBB_UHCON_OFFSET 0x0400 /* Host General Control Register */
+#define AVR32_USBB_UHINT_OFFSET 0x0404 /* Host Global Interrupt Register */
+#define AVR32_USBB_UHINTCLR_OFFSET 0x0408 /* Host Global Interrupt Clear Register */
+#define AVR32_USBB_UHINTSET_OFFSET 0x040c /* Host Global Interrupt Set Register */
+#define AVR32_USBB_UHINTE_OFFSET 0x0410 /* Host Global Interrupt Enable Register */
+#define AVR32_USBB_UHINTECLR_OFFSET 0x0414 /* Host Global Interrupt Enable Clear Register */
+#define AVR32_USBB_UHINTESET_OFFSET 0x0418 /* Host Global Interrupt Enable Set Register */
+#define AVR32_USBB_UPRST_OFFSET 0x041c /* Pipe Enable/Reset Register */
+#define AVR32_USBB_UHFNUM_OFFSET 0x0420 /* Host Frame Number Register */
+#define AVR32_USBB_UHADDR1_OFFSET 0x0424 /* Host Address 1 Register */
+#define AVR32_USBB_UHADDR2_OFFSET 0x0428 /* Host Address 2 Register */
+
+#define AVR32_USBB_UPCFG_OFFSET(n) (0x0500+((n)<<2))
+#define AVR32_USBB_UPCFG0_OFFSET 0x0500 /* Pipe 0 Configuration Register */
+#define AVR32_USBB_UPCFG1_OFFSET 0x0504 /* Pipe 1 Configuration Register */
+#define AVR32_USBB_UPCFG2_OFFSET 0x0508 /* Pipe 2 Configuration Register */
+#define AVR32_USBB_UPCFG3_OFFSET 0x050c /* Pipe 3 Configuration Register */
+#define AVR32_USBB_UPCFG4_OFFSET 0x0510 /* Pipe 4 Configuration Register */
+#define AVR32_USBB_UPCFG5_OFFSET 0x0514 /* Pipe 5 Configuration Register */
+#define AVR32_USBB_UPCFG6_OFFSET 0x0518 /* Pipe 6 Configuration Register */
+
+#define AVR32_USBB_UPSTA_OFFSET(n) (0x0530+((n)<<2))
+#define AVR32_USBB_UPSTA0_OFFSET 0x0530 /* Pipe 0 Status Register */
+#define AVR32_USBB_UPSTA1_OFFSET 0x0534 /* Pipe 1 Status Register */
+#define AVR32_USBB_UPSTA2_OFFSET 0x0538 /* Pipe 2 Status Register */
+#define AVR32_USBB_UPSTA3_OFFSET 0x053c /* Pipe 3 Status Register */
+#define AVR32_USBB_UPSTA4_OFFSET 0x0540 /* Pipe 4 Status Register */
+#define AVR32_USBB_UPSTA5_OFFSET 0x0544 /* Pipe 5 Status Register */
+#define AVR32_USBB_UPSTA6_OFFSET 0x0548 /* Pipe 6 Status Register */
+
+#define AVR32_USBB_UPSTACLR_OFFSET(n) (0x0560+((n)<<2))
+#define AVR32_USBB_UPSTA0CLR_OFFSET 0x0560 /* Pipe 0 Status Clear Register */
+#define AVR32_USBB_UPSTA1CLR_OFFSET 0x0564 /* Pipe 1 Status Clear Register */
+#define AVR32_USBB_UPSTA2CLR_OFFSET 0x0568 /* Pipe 2 Status Clear Register */
+#define AVR32_USBB_UPSTA3CLR_OFFSET 0x056c /* Pipe 3 Status Clear Register */
+#define AVR32_USBB_UPSTA4CLR_OFFSET 0x0570 /* Pipe 4 Status Clear Register */
+#define AVR32_USBB_UPSTA5CLR_OFFSET 0x0574 /* Pipe 5 Status Clear Register */
+#define AVR32_USBB_UPSTA6CLR_OFFSET 0x0578 /* Pipe 6 Status Clear Register */
+
+#define AVR32_USBB_UPSTASET_OFFSET(n) (0x0590+((n)<<2))
+#define AVR32_USBB_UPSTA0SET_OFFSET 0x0590 /* Pipe 0 Status Set Register */
+#define AVR32_USBB_UPSTA1SET_OFFSET 0x0594 /* Pipe 1 Status Set Register */
+#define AVR32_USBB_UPSTA2SET_OFFSET 0x0598 /* Pipe 2 Status Set Register */
+#define AVR32_USBB_UPSTA3SET_OFFSET 0x059c /* Pipe 3 Status Set Register */
+#define AVR32_USBB_UPSTA4SET_OFFSET 0x05a0 /* Pipe 4 Status Set Register */
+#define AVR32_USBB_UPSTA5SET_OFFSET 0x05a4 /* Pipe 5 Status Set Register */
+#define AVR32_USBB_UPSTA6SET_OFFSET 0x05a8 /* Pipe 6 Status Set Register */
+
+#define AVR32_USBB_UPCON_OFFSET(n) (0x05c0+((n)<<2))
+#define AVR32_USBB_UPCON0_OFFSET 0x05c0 /* Pipe 0 Control Register */
+#define AVR32_USBB_UPCON1_OFFSET 0x05c4 /* Pipe 1 Control Register */
+#define AVR32_USBB_UPCON2_OFFSET 0x05c8 /* Pipe 2 Control Register */
+#define AVR32_USBB_UPCON3_OFFSET 0x05cc /* Pipe 3 Control Register */
+#define AVR32_USBB_UPCON4_OFFSET 0x05d0 /* Pipe 4 Control Register */
+#define AVR32_USBB_UPCON5_OFFSET 0x05d4 /* Pipe 5 Control Register */
+#define AVR32_USBB_UPCON6_OFFSET 0x05d8 /* Pipe 6 Control Register */
+
+#define AVR32_USBB_UPCONSET_OFFSET(n) (0x05f0+((n)<<2))
+#define AVR32_USBB_UPCON0SET_OFFSET 0x05f0 /* Pipe 0 Control Set Register */
+#define AVR32_USBB_UPCON1SET_OFFSET 0x05f4 /* Pipe 1 Control Set Register */
+#define AVR32_USBB_UPCON2SET_OFFSET 0x05f8 /* Pipe 2 Control Set Register */
+#define AVR32_USBB_UPCON3SET_OFFSET 0x05fc /* Pipe 3 Control Set Register */
+#define AVR32_USBB_UPCON4SET_OFFSET 0x0600 /* Pipe 4 Control Set Register */
+#define AVR32_USBB_UPCON5SET_OFFSET 0x0604 /* Pipe 5 Control Set Register */
+#define AVR32_USBB_UPCON6SET_OFFSET 0x0608 /* Pipe 6 Control Set Register */
+
+#define AVR32_USBB_UPCONCLR_OFFSET(n) (0x0620+((n)<<2))
+#define AVR32_USBB_UPCON0CLR_OFFSET 0x0620 /* Pipe 0 Control Clear Register */
+#define AVR32_USBB_UPCON1CLR_OFFSET 0x0624 /* Pipe 1 Control Clear Register */
+#define AVR32_USBB_UPCON2CLR_OFFSET 0x0628 /* Pipe 2 Control Clear Register */
+#define AVR32_USBB_UPCON3CLR_OFFSET 0x062c /* Pipe 3 Control Clear Register */
+#define AVR32_USBB_UPCON4CLR_OFFSET 0x0630 /* Pipe 4 Control Clear Register */
+#define AVR32_USBB_UPCON5CLR_OFFSET 0x0634 /* Pipe 5 Control Clear Register */
+#define AVR32_USBB_UPCON6CLR_OFFSET 0x0638 /* Pipe 6 Control Clear Register */
+
+#define AVR32_USBB_UPINRQ_OFFSET(n) (0x0650+((n)<<2))
+#define AVR32_USBB_UPINRQ0_OFFSET 0x0650 /* Pipe 0 IN Request Register */
+#define AVR32_USBB_UPINRQ1_OFFSET 0x0654 /* Pipe 1 IN Request Register */
+#define AVR32_USBB_UPINRQ2_OFFSET 0x0658 /* Pipe 2 IN Request Register */
+#define AVR32_USBB_UPINRQ3_OFFSET 0x065c /* Pipe 3 IN Request Register */
+#define AVR32_USBB_UPINRQ4_OFFSET 0x0660 /* Pipe 4 IN Request Register */
+#define AVR32_USBB_UPINRQ5_OFFSET 0x0664 /* Pipe 5 IN Request Register */
+#define AVR32_USBB_UPINRQ6_OFFSET 0x0668 /* Pipe 6 IN Request Register */
+
+#define AVR32_USBB_UPERR_OFFSET(n) (0x0680+((n)<<2))
+#define AVR32_USBB_UPERR0_OFFSET 0x0680 /* Pipe 0 Error Register */
+#define AVR32_USBB_UPERR1_OFFSET 0x0684 /* Pipe 1 Error Register */
+#define AVR32_USBB_UPERR2_OFFSET 0x0688 /* Pipe 2 Error Register */
+#define AVR32_USBB_UPERR3_OFFSET 0x068c /* Pipe 3 Error Register */
+#define AVR32_USBB_UPERR4_OFFSET 0x0690 /* Pipe 4 Error Register */
+#define AVR32_USBB_UPERR5_OFFSET 0x0694 /* Pipe 5 Error Register */
+#define AVR32_USBB_UPERR6_OFFSET 0x0698 /* Pipe 6 Error Register */
+
+#define AVR32_UHDMA_OFFSET(n) (0x0700+((n)<<4))
+#define AVR32_UHDMA_NEXTDESC_OFFSET 0x0000 /* Host DMA Channel Next Descriptor Address Register */
+#define AVR32_UHDMA_ADDR_OFFSET 0x0004 /* Host DMA Channel HSB Address Register */
+#define AVR32_UHDMA_CTRL_OFFSET 0x0008 /* Host DMA Channel Control Register */
+#define AVR32_UHDMA_STATUS_OFFSET 0x000c /* Host DMA Channel Status Register */
+
+#define AVR32_UHDMA1_NEXTDESC_OFFSET 0x0710 /* Host DMA Channel 1 Next Descriptor Address Register */
+#define AVR32_UHDMA1_ADDR_OFFSET 0x0714 /* Host DMA Channel 1 HSB Address Register */
+#define AVR32_UHDMA1_CTRL_OFFSET 0x0718 /* Host DMA Channel 1 Control Register */
+#define AVR32_UHDMA1_STATUS_OFFSET 0x071c /* Host DMA Channel 1 Status Register */
+
+#define AVR32_UHDMA2_NEXTDESC_OFFSET 0x0720 /* Host DMA Channel 2 Next Descriptor Address Register */
+#define AVR32_UHDMA2_ADDR_OFFSET 0x0724 /* Host DMA Channel 2 HSB Address Register */
+#define AVR32_UHDMA2_CTRL_OFFSET 0x0728 /* Host DMA Channel 2 Control Register */
+#define AVR32_UHDMA2_STATUS_OFFSET 0x072c /* Host DMA Channel 2 Status Register */
+
+#define AVR32_UHDMA3_NEXTDESC_OFFSET 0x0730 /* Host DMA Channel 3 Next Descriptor Address Register */
+#define AVR32_UHDMA3_ADDR_OFFSET 0x0734 /* Host DMA Channel 3 HSB Address Register */
+#define AVR32_UHDMA3_CTRL_OFFSET 0x0738 /* Host DMA Channel 3 Control Register */
+#define AVR32_UHDMA3_STATUS_OFFSET 0x073c /* Host DMA Channel 3 Status Register */
+
+#define AVR32_UHDMA4_NEXTDESC_OFFSET 0x0740 /* Host DMA Channel 4 Next Descriptor Address Register */
+#define AVR32_UHDMA4_ADDR_OFFSET 0x0744 /* Host DMA Channel 4 HSB Address Register */
+#define AVR32_UHDMA4_CTRL_OFFSET 0x0748 /* Host DMA Channel 4 Control Register */
+#define AVR32_UHDMA4_STATUS_OFFSET 0x074c /* Host DMA Channel 4 Status Register */
+
+#define AVR32_UHDMA5_NEXTDESC_OFFSET 0x0750 /* Host DMA Channel 5 Next Descriptor Address Register */
+#define AVR32_UHDMA5_ADDR_OFFSET 0x0754 /* Host DMA Channel 5 HSB Address Register */
+#define AVR32_UHDMA5_CTRL_OFFSET 0x0758 /* Host DMA Channel 5 Control Register */
+#define AVR32_UHDMA5_STATUS_OFFSET 0x075c /* Host DMA Channel 5 Status Register */
+
+#define AVR32_UHDMA6_NEXTDESC_OFFSET 0x0760 /* Host DMA Channel 6 Next Descriptor Address Register */
+#define AVR32_UHDMA6_ADDR_OFFSET 0x0764 /* Host DMA Channel 6 HSB Address Register */
+#define AVR32_UHDMA6_CTRL_OFFSET 0x0768 /* Host DMA Channel 6 Control Register */
+#define AVR32_UHDMA6_STATUS_OFFSET 0x076c /* Host DMA Channel 6 Status Register */
+
+/* USB General Registers */
+
+#define AVR32_USBB_USBCON_OFFSET 0x0800 /* General Control Register */
+#define AVR32_USBB_USBSTA_OFFSET 0x0804 /* General Status Register */
+#define AVR32_USBB_USBSTACLR_OFFSET 0x0808 /* General Status Clear Register */
+#define AVR32_USBB_USBSTASET_OFFSET 0x080c /* General Status Set Register */
+#define AVR32_USBB_UVERS_OFFSET 0x0818 /* IP Version Register */
+#define AVR32_USBB_UFEATURES_OFFSET 0x081c /* IP Features Register */
+#define AVR32_USBB_UADDRSIZE_OFFSET 0x0820 /* IP PB Address Size Register */
+#define AVR32_USBB_UNAME1_OFFSET 0x0824 /* IP Name Register 1 */
+#define AVR32_USBB_UNAME2_OFFSET 0x0828 /* IP Name Register 2 */
+#define AVR32_USBB_USBFSM_OFFSET 0x082c /* USB Finite State Machine Status Register */
+
+/* Register Addresses ***************************************************************/
+
+/* USB Device Registers */
+
+#define AVR32_USBB_UDCON (AVR32_USB_BASE+AVR32_USBB_UDCON_OFFSET)
+#define AVR32_USBB_UDINT (AVR32_USB_BASE+AVR32_USBB_UDINT_OFFSET)
+#define AVR32_USBB_UDINTCLR (AVR32_USB_BASE+AVR32_USBB_UDINTCLR_OFFSET)
+#define AVR32_USBB_UDINTSET (AVR32_USB_BASE+AVR32_USBB_UDINTSET_OFFSET)
+#define AVR32_USBB_UDINTE (AVR32_USB_BASE+AVR32_USBB_UDINTE_OFFSET)
+#define AVR32_USBB_UDINTECLR (AVR32_USB_BASE+AVR32_USBB_UDINTECLR_OFFSET)
+#define AVR32_USBB_UDINTESET (AVR32_USB_BASE+AVR32_USBB_UDINTESET_OFFSET)
+#define AVR32_USBB_UERST (AVR32_USB_BASE+AVR32_USBB_UERST_OFFSET)
+#define AVR32_USBB_UDFNUM (AVR32_USB_BASE+AVR32_USBB_UDFNUM_OFFSET)
+
+#define AVR32_USBB_UECFG(n) (AVR32_USB_BASE+AVR32_USBB_UECFG_OFFSET(n))
+#define AVR32_USBB_UECFG0 (AVR32_USB_BASE+AVR32_USBB_UECFG0_OFFSET)
+#define AVR32_USBB_UECFG1 (AVR32_USB_BASE+AVR32_USBB_UECFG1_OFFSET)
+#define AVR32_USBB_UECFG2 (AVR32_USB_BASE+AVR32_USBB_UECFG2_OFFSET)
+#define AVR32_USBB_UECFG3 (AVR32_USB_BASE+AVR32_USBB_UECFG3_OFFSET)
+#define AVR32_USBB_UECFG4 (AVR32_USB_BASE+AVR32_USBB_UECFG4_OFFSET)
+#define AVR32_USBB_UECFG5 (AVR32_USB_BASE+AVR32_USBB_UECFG5_OFFSET)
+#define AVR32_USBB_UECFG6 (AVR32_USB_BASE+AVR32_USBB_UECFG6_OFFSET)
+
+#define AVR32_USBB_UESTA(n) (AVR32_USB_BASE+AVR32_USBB_UESTA_OFFSET(n))
+#define AVR32_USBB_UESTA0 (AVR32_USB_BASE+AVR32_USBB_UESTA0_OFFSET)
+#define AVR32_USBB_UESTA1 (AVR32_USB_BASE+AVR32_USBB_UESTA1_OFFSET)
+#define AVR32_USBB_UESTA2 (AVR32_USB_BASE+AVR32_USBB_UESTA2_OFFSET)
+#define AVR32_USBB_UESTA3 (AVR32_USB_BASE+AVR32_USBB_UESTA3_OFFSET)
+#define AVR32_USBB_UESTA4 (AVR32_USB_BASE+AVR32_USBB_UESTA4_OFFSET)
+#define AVR32_USBB_UESTA5 (AVR32_USB_BASE+AVR32_USBB_UESTA5_OFFSET)
+#define AVR32_USBB_UESTA6 (AVR32_USB_BASE+AVR32_USBB_UESTA6_OFFSET)
+
+#define AVR32_USBB_UESTACLR(n) (AVR32_USB_BASE+AVR32_USBB_UESTACLR_OFFSET(n))
+#define AVR32_USBB_UESTA0CLR (AVR32_USB_BASE+AVR32_USBB_UESTA0CLR_OFFSET)
+#define AVR32_USBB_UESTA1CLR (AVR32_USB_BASE+AVR32_USBB_UESTA1CLR_OFFSET)
+#define AVR32_USBB_UESTA2CLR (AVR32_USB_BASE+AVR32_USBB_UESTA2CLR_OFFSET)
+#define AVR32_USBB_UESTA3CLR (AVR32_USB_BASE+AVR32_USBB_UESTA3CLR_OFFSET)
+#define AVR32_USBB_UESTA4CLR (AVR32_USB_BASE+AVR32_USBB_UESTA4CLR_OFFSET)
+#define AVR32_USBB_UESTA5CLR (AVR32_USB_BASE+AVR32_USBB_UESTA5CLR_OFFSET)
+#define AVR32_USBB_UESTA6CLR (AVR32_USB_BASE+AVR32_USBB_UESTA6CLR_OFFSET)
+
+#define AVR32_USBB_UESTASET(n) (AVR32_USB_BASE+AVR32_USBB_UESTASET_OFFSET(n))
+#define AVR32_USBB_UESTA0SET (AVR32_USB_BASE+AVR32_USBB_UESTA0SET_OFFSET)
+#define AVR32_USBB_UESTA1SET (AVR32_USB_BASE+AVR32_USBB_UESTA1SET_OFFSET)
+#define AVR32_USBB_UESTA2SET (AVR32_USB_BASE+AVR32_USBB_UESTA2SET_OFFSET)
+#define AVR32_USBB_UESTA3SET (AVR32_USB_BASE+AVR32_USBB_UESTA3SET_OFFSET)
+#define AVR32_USBB_UESTA4SET (AVR32_USB_BASE+AVR32_USBB_UESTA4SET_OFFSET)
+#define AVR32_USBB_UESTA5SET (AVR32_USB_BASE+AVR32_USBB_UESTA5SET_OFFSET)
+#define AVR32_USBB_UESTA6SET (AVR32_USB_BASE+AVR32_USBB_UESTA6SET_OFFSET)
+
+#define AVR32_USBB_UECON(n) (AVR32_USB_BASE+AVR32_USBB_UECON_OFFSET(n))
+#define AVR32_USBB_UECON0 (AVR32_USB_BASE+AVR32_USBB_UECON0_OFFSET)
+#define AVR32_USBB_UECON1 (AVR32_USB_BASE+AVR32_USBB_UECON1_OFFSET)
+#define AVR32_USBB_UECON2 (AVR32_USB_BASE+AVR32_USBB_UECON2_OFFSET)
+#define AVR32_USBB_UECON3 (AVR32_USB_BASE+AVR32_USBB_UECON3_OFFSET)
+#define AVR32_USBB_UECON4 (AVR32_USB_BASE+AVR32_USBB_UECON4_OFFSET)
+#define AVR32_USBB_UECON5 (AVR32_USB_BASE+AVR32_USBB_UECON5_OFFSET)
+#define AVR32_USBB_UECON6 (AVR32_USB_BASE+AVR32_USBB_UECON6_OFFSET)
+
+#define AVR32_USBB_UECONSET(n) (AVR32_USB_BASE+AVR32_USBB_UECONSET_OFFSET(n))
+#define AVR32_USBB_UECON0SET (AVR32_USB_BASE+AVR32_USBB_UECON0SET_OFFSET)
+#define AVR32_USBB_UECON1SET (AVR32_USB_BASE+AVR32_USBB_UECON1SET_OFFSET)
+#define AVR32_USBB_UECON2SET (AVR32_USB_BASE+AVR32_USBB_UECON2SET_OFFSET)
+#define AVR32_USBB_UECON3SET (AVR32_USB_BASE+AVR32_USBB_UECON3SET_OFFSET)
+#define AVR32_USBB_UECON4SET (AVR32_USB_BASE+AVR32_USBB_UECON4SET_OFFSET)
+#define AVR32_USBB_UECON5SET (AVR32_USB_BASE+AVR32_USBB_UECON5SET_OFFSET)
+#define AVR32_USBB_UECON6SET (AVR32_USB_BASE+AVR32_USBB_UECON6SET_OFFSET)
+
+#define AVR32_USBB_UECONCLR(n) (AVR32_USB_BASE+AVR32_USBB_UECONCLR_OFFSET(n))
+#define AVR32_USBB_UECON0CLR (AVR32_USB_BASE+AVR32_USBB_UECON0CLR_OFFSET)
+#define AVR32_USBB_UECON1CLR (AVR32_USB_BASE+AVR32_USBB_UECON1CLR_OFFSET)
+#define AVR32_USBB_UECON2CLR (AVR32_USB_BASE+AVR32_USBB_UECON2CLR_OFFSET)
+#define AVR32_USBB_UECON3CLR (AVR32_USB_BASE+AVR32_USBB_UECON3CLR_OFFSET)
+#define AVR32_USBB_UECON4CLR (AVR32_USB_BASE+AVR32_USBB_UECON4CLR_OFFSET)
+#define AVR32_USBB_UECON5CLR (AVR32_USB_BASE+AVR32_USBB_UECON5CLR_OFFSET)
+#define AVR32_USBB_UECON6CLR (AVR32_USB_BASE+AVR32_USBB_UECON6CLR_OFFSET)
+
+#define AVR32_UDDMA_BASE(n) (AVR32_USB_BASE+AVR32_UDDMA_OFFSET(n))
+#define AVR32_UDDMA_NEXTDESC(n) (AVR32_UDDMA_BASE(n)+AVR32_UDDMA_NEXTDESC_OFFSET)
+#define AVR32_UDDMA_ADDR(n) (AVR32_UDDMA_BASE(n)+AVR32_UDDMA_ADDR_OFFSET)
+#define AVR32_UDDMA_CTRL(n) (AVR32_UDDMA_BASE(n)+AVR32_UDDMA_CTRL_OFFSET)
+#define AVR32_UDDMA_STATUS(n) (AVR32_UDDMA_BASE(n)+AVR32_UDDMA_STATUS_OFFSET)
+
+#define AVR32_UDDMA1_NEXTDESC (AVR32_USB_BASE+AVR32_UDDMA1_NEXTDESC_OFFSET)
+#define AVR32_UDDMA1_ADDR (AVR32_USB_BASE+AVR32_UDDMA1_ADDR_OFFSET)
+#define AVR32_UDDMA1_CTRL (AVR32_USB_BASE+AVR32_UDDMA1_CTRL_OFFSET)
+#define AVR32_UDDMA1_STATUS (AVR32_USB_BASE+AVR32_UDDMA1_STATUS_OFFSET)
+
+#define AVR32_UDDMA2_NEXTDESC (AVR32_USB_BASE+AVR32_UDDMA2_NEXTDESC_OFFSET)
+#define AVR32_UDDMA2_ADDR (AVR32_USB_BASE+AVR32_UDDMA2_ADDR_OFFSET)
+#define AVR32_UDDMA2_CTRL (AVR32_USB_BASE+AVR32_UDDMA2_CTRL_OFFSET)
+#define AVR32_UDDMA2_STATUS (AVR32_USB_BASE+AVR32_UDDMA2_STATUS_OFFSET)
+
+#define AVR32_UDDMA3_NEXTDESC (AVR32_USB_BASE+AVR32_UDDMA3_NEXTDESC_OFFSET)
+#define AVR32_UDDMA3_ADDR (AVR32_USB_BASE+AVR32_UDDMA3_ADDR_OFFSET)
+#define AVR32_UDDMA3_CTRL (AVR32_USB_BASE+AVR32_UDDMA3_CTRL_OFFSET)
+#define AVR32_UDDMA3_STATUS (AVR32_USB_BASE+AVR32_UDDMA3_STATUS_OFFSET)
+
+#define AVR32_UDDMA4_NEXTDESC (AVR32_USB_BASE+AVR32_UDDMA4_NEXTDESC_OFFSET)
+#define AVR32_UDDMA4_ADDR (AVR32_USB_BASE+AVR32_UDDMA4_ADDR_OFFSET )
+#define AVR32_UDDMA4_CTRL (AVR32_USB_BASE+AVR32_UDDMA4_CTRL_OFFSET)
+#define AVR32_UDDMA4_STATUS (AVR32_USB_BASE+AVR32_UDDMA4_STATUS_OFFSET)
+
+#define AVR32_UDDMA5_NEXTDESC (AVR32_USB_BASE+AVR32_UDDMA5_NEXTDESC_OFFSET)
+#define AVR32_UDDMA5_ADDR (AVR32_USB_BASE+AVR32_UDDMA5_ADDR_OFFSET)
+#define AVR32_UDDMA5_CTRL (AVR32_USB_BASE+AVR32_UDDMA5_CTRL_OFFSET)
+#define AVR32_UDDMA5_STATUS (AVR32_USB_BASE+AVR32_UDDMA5_STATUS_OFFSET)
+
+#define AVR32_UDDMA6_NEXTDESC (AVR32_USB_BASE+AVR32_UDDMA6_NEXTDESC_OFFSET)
+#define AVR32_UDDMA6_ADDR (AVR32_USB_BASE+AVR32_UDDMA6_ADDR_OFFSET)
+#define AVR32_UDDMA6_CTRL (AVR32_USB_BASE+AVR32_UDDMA6_CTRL_OFFSET)
+#define AVR32_UDDMA6_STATUS (AVR32_USB_BASE+AVR32_UDDMA6_STATUS_OFFSET)
+
+/* USB Host Registers */
+
+#define AVR32_USBB_UHCON (AVR32_USB_BASE+AVR32_USBB_UHCON_OFFSET)
+#define AVR32_USBB_UHINT (AVR32_USB_BASE+AVR32_USBB_UHINT_OFFSET)
+#define AVR32_USBB_UHINTCLR (AVR32_USB_BASE+AVR32_USBB_UHINTCLR_OFFSET)
+#define AVR32_USBB_UHINTSET (AVR32_USB_BASE+AVR32_USBB_UHINTSET_OFFSET)
+#define AVR32_USBB_UHINTE (AVR32_USB_BASE+AVR32_USBB_UHINTE_OFFSET)
+#define AVR32_USBB_UHINTECLR (AVR32_USB_BASE+AVR32_USBB_UHINTECLR_OFFSET)
+#define AVR32_USBB_UHINTESET (AVR32_USB_BASE+AVR32_USBB_UHINTESET_OFFSET)
+#define AVR32_USBB_UPRST (AVR32_USB_BASE+AVR32_USBB_UPRST_OFFSET)
+#define AVR32_USBB_UHFNUM (AVR32_USB_BASE+AVR32_USBB_UHFNUM_OFFSET)
+#define AVR32_USBB_UHADDR1 (AVR32_USB_BASE+AVR32_USBB_UHADDR1_OFFSET)
+#define AVR32_USBB_UHADDR2 (AVR32_USB_BASE+AVR32_USBB_UHADDR2_OFFSET)
+
+#define AVR32_USBB_UPCFG(n) (AVR32_USB_BASE+AVR32_USBB_UPCFG_OFFSET(n))
+#define AVR32_USBB_UPCFG0 (AVR32_USB_BASE+AVR32_USBB_UPCFG0_OFFSET)
+#define AVR32_USBB_UPCFG1 (AVR32_USB_BASE+AVR32_USBB_UPCFG1_OFFSET)
+#define AVR32_USBB_UPCFG2 (AVR32_USB_BASE+AVR32_USBB_UPCFG2_OFFSET)
+#define AVR32_USBB_UPCFG3 (AVR32_USB_BASE+AVR32_USBB_UPCFG3_OFFSET)
+#define AVR32_USBB_UPCFG4 (AVR32_USB_BASE+AVR32_USBB_UPCFG4_OFFSET)
+#define AVR32_USBB_UPCFG5 (AVR32_USB_BASE+AVR32_USBB_UPCFG5_OFFSET)
+#define AVR32_USBB_UPCFG6 (AVR32_USB_BASE+AVR32_USBB_UPCFG6_OFFSET)
+
+#define AVR32_USBB_UPSTA(n) (AVR32_USB_BASE+AVR32_USBB_UPSTA_OFFSET(n))
+#define AVR32_USBB_UPSTA0 (AVR32_USB_BASE+AVR32_USBB_UPSTA0_OFFSET)
+#define AVR32_USBB_UPSTA1 (AVR32_USB_BASE+AVR32_USBB_UPSTA1_OFFSET)
+#define AVR32_USBB_UPSTA2 (AVR32_USB_BASE+AVR32_USBB_UPSTA2_OFFSET)
+#define AVR32_USBB_UPSTA3 (AVR32_USB_BASE+AVR32_USBB_UPSTA3_OFFSET)
+#define AVR32_USBB_UPSTA4 (AVR32_USB_BASE+AVR32_USBB_UPSTA4_OFFSET)
+#define AVR32_USBB_UPSTA5 (AVR32_USB_BASE+AVR32_USBB_UPSTA5_OFFSET)
+#define AVR32_USBB_UPSTA6 (AVR32_USB_BASE+AVR32_USBB_UPSTA6_OFFSET)
+
+#define AVR32_USBB_UPSTACLR(n) (AVR32_USB_BASE+AVR32_USBB_UPSTACLR_OFFSET(n))
+#define AVR32_USBB_UPSTA0CLR (AVR32_USB_BASE+AVR32_USBB_UPSTA0CLR_OFFSET)
+#define AVR32_USBB_UPSTA1CLR (AVR32_USB_BASE+AVR32_USBB_UPSTA1CLR_OFFSET)
+#define AVR32_USBB_UPSTA2CLR (AVR32_USB_BASE+AVR32_USBB_UPSTA2CLR_OFFSET)
+#define AVR32_USBB_UPSTA3CLR (AVR32_USB_BASE+AVR32_USBB_UPSTA3CLR_OFFSET)
+#define AVR32_USBB_UPSTA4CLR (AVR32_USB_BASE+AVR32_USBB_UPSTA4CLR_OFFSET)
+#define AVR32_USBB_UPSTA5CLR (AVR32_USB_BASE+AVR32_USBB_UPSTA5CLR_OFFSET)
+#define AVR32_USBB_UPSTA6CLR (AVR32_USB_BASE+AVR32_USBB_UPSTA6CLR_OFFSET)
+
+#define AVR32_USBB_UPSTASET(n) (AVR32_USB_BASE+AVR32_USBB_UPSTASET_OFFSET(n))
+#define AVR32_USBB_UPSTA0SET (AVR32_USB_BASE+AVR32_USBB_UPSTA0SET_OFFSET)
+#define AVR32_USBB_UPSTA1SET (AVR32_USB_BASE+AVR32_USBB_UPSTA1SET_OFFSET)
+#define AVR32_USBB_UPSTA2SET (AVR32_USB_BASE+AVR32_USBB_UPSTA2SET_OFFSET)
+#define AVR32_USBB_UPSTA3SET (AVR32_USB_BASE+AVR32_USBB_UPSTA3SET_OFFSET)
+#define AVR32_USBB_UPSTA4SET (AVR32_USB_BASE+AVR32_USBB_UPSTA4SET_OFFSET)
+#define AVR32_USBB_UPSTA5SET (AVR32_USB_BASE+AVR32_USBB_UPSTA5SET_OFFSET)
+#define AVR32_USBB_UPSTA6SET (AVR32_USB_BASE+AVR32_USBB_UPSTA6SET_OFFSET)
+
+#define AVR32_USBB_UPCON(n) (AVR32_USB_BASE+AVR32_USBB_UPCON_OFFSET(n))
+#define AVR32_USBB_UPCON0 (AVR32_USB_BASE+AVR32_USBB_UPCON0_OFFSET)
+#define AVR32_USBB_UPCON1 (AVR32_USB_BASE+AVR32_USBB_UPCON1_OFFSET)
+#define AVR32_USBB_UPCON2 (AVR32_USB_BASE+AVR32_USBB_UPCON2_OFFSET)
+#define AVR32_USBB_UPCON3 (AVR32_USB_BASE+AVR32_USBB_UPCON3_OFFSET)
+#define AVR32_USBB_UPCON4 (AVR32_USB_BASE+AVR32_USBB_UPCON4_OFFSET)
+#define AVR32_USBB_UPCON5 (AVR32_USB_BASE+AVR32_USBB_UPCON5_OFFSET)
+#define AVR32_USBB_UPCON6 (AVR32_USB_BASE+AVR32_USBB_UPCON6_OFFSET)
+
+#define AVR32_USBB_UPCONSET(n) (AVR32_USB_BASE+AVR32_USBB_UPCONSET_OFFSET(n))
+#define AVR32_USBB_UPCON0SET (AVR32_USB_BASE+AVR32_USBB_UPCON0SET_OFFSET)
+#define AVR32_USBB_UPCON1SET (AVR32_USB_BASE+AVR32_USBB_UPCON1SET_OFFSET)
+#define AVR32_USBB_UPCON2SET (AVR32_USB_BASE+AVR32_USBB_UPCON2SET_OFFSET)
+#define AVR32_USBB_UPCON3SET (AVR32_USB_BASE+AVR32_USBB_UPCON3SET_OFFSET)
+#define AVR32_USBB_UPCON4SET (AVR32_USB_BASE+AVR32_USBB_UPCON4SET_OFFSET)
+#define AVR32_USBB_UPCON5SET (AVR32_USB_BASE+AVR32_USBB_UPCON5SET_OFFSET)
+#define AVR32_USBB_UPCON6SET (AVR32_USB_BASE+AVR32_USBB_UPCON6SET_OFFSET)
+
+#define AVR32_USBB_UPCONCLR(n) (AVR32_USB_BASE+AVR32_USBB_UPCONCLR_OFFSET(n))
+#define AVR32_USBB_UPCON0CLR (AVR32_USB_BASE+AVR32_USBB_UPCON0CLR_OFFSET)
+#define AVR32_USBB_UPCON1CLR (AVR32_USB_BASE+AVR32_USBB_UPCON1CLR_OFFSET)
+#define AVR32_USBB_UPCON2CLR (AVR32_USB_BASE+AVR32_USBB_UPCON2CLR_OFFSET)
+#define AVR32_USBB_UPCON3CLR (AVR32_USB_BASE+AVR32_USBB_UPCON3CLR_OFFSET)
+#define AVR32_USBB_UPCON4CLR (AVR32_USB_BASE+AVR32_USBB_UPCON4CLR_OFFSET)
+#define AVR32_USBB_UPCON5CLR (AVR32_USB_BASE+AVR32_USBB_UPCON5CLR_OFFSET)
+#define AVR32_USBB_UPCON6CLR (AVR32_USB_BASE+AVR32_USBB_UPCON6CLR_OFFSET)
+
+#define AVR32_USBB_UPINRQ(n) (AVR32_USB_BASE+AVR32_USBB_UPINRQ_OFFSET(n))
+#define AVR32_USBB_UPINRQ0 (AVR32_USB_BASE+AVR32_USBB_UPINRQ0_OFFSET)
+#define AVR32_USBB_UPINRQ1 (AVR32_USB_BASE+AVR32_USBB_UPINRQ1_OFFSET)
+#define AVR32_USBB_UPINRQ2 (AVR32_USB_BASE+AVR32_USBB_UPINRQ2_OFFSET)
+#define AVR32_USBB_UPINRQ3 (AVR32_USB_BASE+AVR32_USBB_UPINRQ3_OFFSET)
+#define AVR32_USBB_UPINRQ4 (AVR32_USB_BASE+AVR32_USBB_UPINRQ4_OFFSET)
+#define AVR32_USBB_UPINRQ5 (AVR32_USB_BASE+AVR32_USBB_UPINRQ5_OFFSET)
+#define AVR32_USBB_UPINRQ6 (AVR32_USB_BASE+AVR32_USBB_UPINRQ6_OFFSET)
+
+#define AVR32_USBB_UPERR(n) (AVR32_USB_BASE+AVR32_USBB_UPERR_OFFSET(n))
+#define AVR32_USBB_UPERR0 (AVR32_USB_BASE+AVR32_USBB_UPERR0_OFFSET)
+#define AVR32_USBB_UPERR1 (AVR32_USB_BASE+AVR32_USBB_UPERR1_OFFSET)
+#define AVR32_USBB_UPERR2 (AVR32_USB_BASE+AVR32_USBB_UPERR2_OFFSET)
+#define AVR32_USBB_UPERR3 (AVR32_USB_BASE+AVR32_USBB_UPERR3_OFFSET)
+#define AVR32_USBB_UPERR4 (AVR32_USB_BASE+AVR32_USBB_UPERR4_OFFSET)
+#define AVR32_USBB_UPERR5 (AVR32_USB_BASE+AVR32_USBB_UPERR5_OFFSET)
+#define AVR32_USBB_UPERR6 (AVR32_USB_BASE+AVR32_USBB_UPERR6_OFFSET)
+
+#define AVR32_UHDMA_BASE(n) (AVR32_USB_BASE+AVR32_UHDMA_OFFSET(n))
+#define AVR32_UHDMA_NEXTDESC(n) (AVR32_UHDMA_BASE(n)+AVR32_UHDMA_NEXTDESC_OFFSET)
+#define AVR32_UHDMA_ADDR(n) (AVR32_UHDMA_BASE(n)+AVR32_UHDMA_ADDR_OFFSET)
+#define AVR32_UHDMA_CTRL(n) (AVR32_UHDMA_BASE(n)+AVR32_UHDMA_CTRL_OFFSET)
+#define AVR32_UHDMA_STATUS(n) (AVR32_UHDMA_BASE(n)+AVR32_UHDMA_STATUS_OFFSET)
+
+#define AVR32_UHDMA1_NEXTDESC (AVR32_USB_BASE+AVR32_UHDMA1_NEXTDESC_OFFSET)
+#define AVR32_UHDMA1_ADDR (AVR32_USB_BASE+AVR32_UHDMA1_ADDR_OFFSET)
+#define AVR32_UHDMA1_CTRL (AVR32_USB_BASE+AVR32_UHDMA1_CTRL_OFFSET)
+#define AVR32_UHDMA1_STATUS (AVR32_USB_BASE+AVR32_UHDMA1_STATUS_OFFSET)
+
+#define AVR32_UHDMA2_NEXTDESC (AVR32_USB_BASE+AVR32_UHDMA2_NEXTDESC_OFFSET)
+#define AVR32_UHDMA2_ADDR (AVR32_USB_BASE+AVR32_UHDMA2_ADDR_OFFSET)
+#define AVR32_UHDMA2_CTRL (AVR32_USB_BASE+AVR32_UHDMA2_CTRL_OFFSET)
+#define AVR32_UHDMA2_STATUS (AVR32_USB_BASE+AVR32_UHDMA2_STATUS_OFFSET)
+
+#define AVR32_UHDMA3_NEXTDESC (AVR32_USB_BASE+AVR32_UHDMA3_NEXTDESC_OFFSET)
+#define AVR32_UHDMA3_ADDR (AVR32_USB_BASE+AVR32_UHDMA3_ADDR_OFFSET)
+#define AVR32_UHDMA3_CTRL (AVR32_USB_BASE+AVR32_UHDMA3_CTRL_OFFSET)
+#define AVR32_UHDMA3_STATUS (AVR32_USB_BASE+AVR32_UHDMA3_STATUS_OFFSET)
+
+#define AVR32_UHDMA4_NEXTDESC (AVR32_USB_BASE+AVR32_UHDMA4_NEXTDESC_OFFSET)
+#define AVR32_UHDMA4_ADDR (AVR32_USB_BASE+AVR32_UHDMA4_ADDR_OFFSET)
+#define AVR32_UHDMA4_CTRL (AVR32_USB_BASE+AVR32_UHDMA4_CTRL_OFFSET)
+#define AVR32_UHDMA4_STATUS (AVR32_USB_BASE+AVR32_UHDMA4_STATUS_OFFSET)
+
+#define AVR32_UHDMA5_NEXTDESC (AVR32_USB_BASE+AVR32_UHDMA5_NEXTDESC_OFFSET)
+#define AVR32_UHDMA5_ADDR (AVR32_USB_BASE+AVR32_UHDMA5_ADDR_OFFSET)
+#define AVR32_UHDMA5_CTRL (AVR32_USB_BASE+AVR32_UHDMA5_CTRL_OFFSET)
+#define AVR32_UHDMA5_STATUS (AVR32_USB_BASE+AVR32_UHDMA5_STATUS_OFFSET)
+
+#define AVR32_UHDMA6_NEXTDESC (AVR32_USB_BASE+AVR32_UHDMA6_NEXTDESC_OFFSET)
+#define AVR32_UHDMA6_ADDR (AVR32_USB_BASE+AVR32_UHDMA6_ADDR_OFFSET)
+#define AVR32_UHDMA6_CTRL (AVR32_USB_BASE+AVR32_UHDMA6_CTRL_OFFSET)
+#define AVR32_UHDMA6_STATUS (AVR32_USB_BASE+AVR32_UHDMA6_STATUS_OFFSET)
+
+/* USB General Registers */
+
+#define AVR32_USBB_USBCON (AVR32_USB_BASE+AVR32_USBB_USBCON_OFFSET)
+#define AVR32_USBB_USBSTA (AVR32_USB_BASE+AVR32_USBB_USBSTA_OFFSET)
+#define AVR32_USBB_USBSTACLR (AVR32_USB_BASE+AVR32_USBB_USBSTACLR_OFFSET)
+#define AVR32_USBB_USBSTASET (AVR32_USB_BASE+AVR32_USBB_USBSTASET_OFFSET)
+#define AVR32_USBB_UVERS (AVR32_USB_BASE+AVR32_USBB_UVERS_OFFSET)
+#define AVR32_USBB_UFEATURES (AVR32_USB_BASE+AVR32_USBB_UFEATURES_OFFSET)
+#define AVR32_USBB_UADDRSIZE (AVR32_USB_BASE+AVR32_USBB_UADDRSIZE_OFFSET)
+#define AVR32_USBB_UNAME1 (AVR32_USB_BASE+AVR32_USBB_UNAME1_OFFSET)
+#define AVR32_USBB_UNAME2 (AVR32_USB_BASE+AVR32_USBB_UNAME2_OFFSET)
+#define AVR32_USBB_USBFSM (AVR32_USB_BASE+AVR32_USBB_USBFSM_OFFSET)
+
+/* Register Bit-field Definitions ***************************************************/
+/* USB Device Registers Bit-field Definitions ***************************************/
+/* Device General Control Register Bit-field Definitions */
+
+#define USBB_UDCON_UADD_SHIFT (0) /* Bits 0-6: USB Address */
+#define USBB_UDCON_UADD_MASK (0x7f << USBB_UDCON_UADD_SHIFT)
+#define USBB_UDCON_ADDEN: (1 << 7) /* Bit 7: Address Enable */
+#define USBB_UDCON_DETACH (1 << 8) /* Bit 8: Detach */
+#define USBB_UDCON_RMWKUP (1 << 9) /* Bit 9: Remote Wake-Up */
+#define USBB_UDCON_LS (1 << 12) /* Bit 12: Low-Speed Mode Force */
+
+/* Device Global Interrupt Register Bit-field Definitions */
+/* Device Global Interrupt Clear Register Bit-field Definitions */
+/* Device Global Interrupt Set Register Bit-field Definitions */
+/* Device Global Interrupt Enable Register Bit-field Definitions */
+/* Device Global Interrupt Enable Clear Register Bit-field Definitions */
+/* Device Global Interrupt Enable Set Register Bit-field Definitions */
+
+#define USBB_UDINT_SUSP (1 << 0) /* Bit 0: Suspend Interrupt */
+#define USBB_UDINT_SOF (1 << 2) /* Bit 2: Start of Frame Interrupt */
+#define USBB_UDINT_EORST (1 << 3) /* Bit 3: End of Reset Interrupt */
+#define USBB_UDINT_WAKEUP (1 << 4) /* Bit 4: Wake-Up Interrupt */
+#define USBB_UDINT_EORSM (1 << 5) /* Bit 5: End of Resume Interrupt */
+#define USBB_UDINT_UPRSM (1 << 6) /* Bit 6: Upstream Resume Interrupt */
+#define USBB_UDINT_EPINT(n) (1 << ((n)+12)) /* Endpoint n Interrupt */
+#define USBB_UDINT_EP0INT (1 << 12) /* Bit 12: Endpoint n Interrupt */
+#define USBB_UDINT_EP1INT (1 << 13) /* Bit 13: Endpoint n Interrupt */
+#define USBB_UDINT_EP2INT (1 << 14) /* Bit 14: Endpoint n Interrupt */
+#define USBB_UDINT_EP3INT (1 << 15) /* Bit 15: Endpoint n Interrupt */
+#define USBB_UDINT_EP4INT (1 << 16) /* Bit 16: Endpoint n Interrupt */
+#define USBB_UDINT_EP5INT (1 << 17) /* Bit 17: Endpoint n Interrupt */
+#define USBB_UDINT_EP6INT (1 << 18) /* Bit 18: Endpoint n Interrupt */
+#define USBB_UDINT_DMAINT(n) (1 << ((n)+24)) /* DMA Channel n Interrupt */
+#define USBB_UDINT_DMA1INT (1 << 25) /* Bit 25: DMA Channel n Interrupt */
+#define USBB_UDINT_DMA2INT (1 << 26) /* Bit 26: DMA Channel 1 Interrupt */
+#define USBB_UDINT_DMA3INT (1 << 27) /* Bit 27: DMA Channel 2 Interrupt */
+#define USBB_UDINT_DMA4INT (1 << 28) /* Bit 28: DMA Channel 3 Interrupt */
+#define USBB_UDINT_DMA5INT (1 << 29) /* Bit 29: DMA Channel 4 Interrupt */
+#define USBB_UDINT_DMA6INT (1 << 30) /* Bit 30: DMA Channel 5 Interrupt */
+
+/* Endpoint Enable/Reset Register Bit-field Definitions */
+
+#define USBB_UERST_EPRST(n) (1 << ((n)+16)) /* Endpoint n Reset */
+#define USBB_UERST_EPRST0 (1 << 16) /* Bit 16: Endpoint 0 Reset */
+#define USBB_UERST_EPRST1 (1 << 17) /* Bit 17: Endpoint 1 Reset */
+#define USBB_UERST_EPRST2 (1 << 18) /* Bit 18: Endpoint 2 Reset */
+#define USBB_UERST_EPRST3 (1 << 19) /* Bit 19: Endpoint 3 Reset */
+#define USBB_UERST_EPRST4 (1 << 20) /* Bit 20: Endpoint 4 Reset */
+#define USBB_UERST_EPRST5 (1 << 21) /* Bit 21: Endpoint 5 Reset */
+#define USBB_UERST_EPRST6 (1 << 22) /* Bit 22: Endpoint 6 Reset */
+#define USBB_UERST_EPEN(n) (1 << n) /* Endpoint n Enable */
+#define USBB_UERST_EPEN0 (1 << 0) /* Bit 0: Endpoint 0 Enable */
+#define USBB_UERST_EPEN1 (1 << 1) /* Bit 1: Endpoint 1 Enable */
+#define USBB_UERST_EPEN2 (1 << 2) /* Bit 2: Endpoint 2 Enable */
+#define USBB_UERST_EPEN3 (1 << 3) /* Bit 3: Endpoint 3 Enable */
+#define USBB_UERST_EPEN4 (1 << 4) /* Bit 4: Endpoint 4 Enable */
+#define USBB_UERST_EPEN5 (1 << 5) /* Bit 5: Endpoint 5 Enable */
+#define USBB_UERST_EPEN6 (1 << 6) /* Bit 5: Endpoint 6 Enable */
+
+/* Device Frame Number Register Bit-field Definitions */
+
+#define USBB_UDFNUM_FNUM_SHIFT (3) /* Bits 3-13: Frame Number */
+#define USBB_UDFNUM_FNUM_MASK (0x7ff << USBB_UDFNUM_FNUM_SHIFT)
+#define USBB_UDFNUM_FNCERR (1 << 15) /* Bit 15: Frame Number CRC Error */
+
+/* Endpoint Configuration Register Bit-field Definitions */
+
+#define USBB_UECFG_ALLOC (1 << 1) /* Bit 1: Endpoint Memory Allocate */
+#define USBB_UECFG_EPBK_SHIFT (2) /* Bits 2-3: Endpoint Banks */
+#define USBB_UECFG_EPBK_MASK (3 << USBB_UECFG_EPBK_SHIFT)
+# define USBB_UECFG_EPBK_1 (0 << USBB_UECFG_EPBK_SHIFT) /* 1 (single-bank endpoint) */
+# define USBB_UECFG_EPBK_2 (1 << USBB_UECFG_EPBK_SHIFT) /* 2 (double-bank endpoint) */
+# define USBB_UECFG_EPBK_3 (2 << USBB_UECFG_EPBK_SHIFT) /* 3 (triple-bank endpoint) */
+#define USBB_UECFG_EPSIZE_SHIFT (4) /* Bits 4-6: Endpoint Size */
+#define USBB_UECFG_EPSIZE_MASK (7 << USBB_UECFG_EPSIZE_SHIFT)
+# define USBB_UECFG_EPSIZE_8 (0 << USBB_UECFG_EPSIZE_SHIFT) /* 8 bytes */
+# define USBB_UECFG_EPSIZE_16 (1 << USBB_UECFG_EPSIZE_SHIFT) /* 16 bytes */
+# define USBB_UECFG_EPSIZE_32 (2 << USBB_UECFG_EPSIZE_SHIFT) /* 32 bytes */
+# define USBB_UECFG_EPSIZE_64 (3 << USBB_UECFG_EPSIZE_SHIFT) /* 64 bytes */
+# define USBB_UECFG_EPSIZE_128 (4 << USBB_UECFG_EPSIZE_SHIFT) /* 128 bytes */
+# define USBB_UECFG_EPSIZE_256 (5 << USBB_UECFG_EPSIZE_SHIFT) /* 256 bytes */
+# define USBB_UECFG_EPSIZE_512 (6 << USBB_UECFG_EPSIZE_SHIFT) /* 512 bytes */
+# define USBB_UECFG_EPSIZE_1024 (7 << USBB_UECFG_EPSIZE_SHIFT) /* 1024 bytes */
+#define USBB_UECFG_EPDIR (1 << 8) /* Bit 8: Endpoint Direction */
+#define USBB_UECFG_AUTOSW (1 << 9) /* Bit 9: Automatic Switch */
+#define USBB_UECFG_EPTYPE_SHIFT (11) /* Bits 11-12: Endpoint Type */
+#define USBB_UECFG_EPTYPE_MASK (3 << USBB_UECFG_EPTYPE_SHIFT)
+# define USBB_UECFG_EPTYPE_CTRL (0 << USBB_UECFG_EPTYPE_SHIFT) /* Control */
+# define USBB_UECFG_EPTYPE_ISOC (1 << USBB_UECFG_EPTYPE_SHIFT) /* Isochronous */
+# define USBB_UECFG_EPTYPE_BULK (2 << USBB_UECFG_EPTYPE_SHIFT) /* Bulk */
+# define USBB_UECFG_EPTYPE_INTR (3 << USBB_UECFG_EPTYPE_SHIFT) /* Interrupt */
+
+/* Endpoint Status Register Bit-field Definitions (common fields) */
+/* Endpoint Status Clear Register Bit-field Definitions */
+/* Endpoint Status Set Register Bit-field Definitions (common fields) */
+
+#define USBB_UESTA_TXINI (1 << 0) /* Bit 0: Transmitted IN Data Interrupt */
+#define USBB_UESTA_RXOUTI (1 << 1) /* Bit 1: Received OUT Data Interrupt */
+#define USBB_UESTA_UNDERFI (1 << 2) /* Bit 2: Underflow Interrupt */
+#define USBB_UESTA_RXSTPI (1 << 2) /* Bit 2: Received SETUP Interrupt */
+#define USBB_UESTA_NAKOUTI (1 << 3) /* Bit 3: NAKed OUT Interrupt */
+#define USBB_UESTA_NAKINI (1 << 4) /* Bit 4: NAKed IN Interrupt */
+#define USBB_UESTA_OVERFI (1 << 5) /* Bit 5: Overflow Interrupt */
+#define USBB_UESTA_STALLEDI (1 << 6) /* Bit 6: STALLed Interrupt */
+#define USBB_UESTA_CRCERRI (1 << 6) /* Bit 6: CRC Error Interrupt */
+#define USBB_UESTA_SHORTPACKET (1 << 7) /* Bit 7: Short Packet Interrupt */
+
+/* Endpoint Status Register Bit-field Definitions (only in UESTA) */
+
+#define USBB_UESTA_DTSEQ_SHIFT (8) /* Bits 8-9: Data Toggle Sequence */
+#define USBB_UESTA_DTSEQ_MASK (3 << USBB_UESTA_DTSEQ_SHIFT)
+# define USBB_UESTA_DTSEQ_DATA0 (0 << USBB_UESTA_DTSEQ_SHIFT) /* Data0 */
+# define USBB_UESTA_DTSEQ_DATA1 (1 << USBB_UESTA_DTSEQ_SHIFT) /* Data1 */
+#define USBB_UESTA_NBUSYBK_SHIFT (12) /* Bits 12-13: Number of Busy Banks */
+#define USBB_UESTA_NBUSYBK_MASK (3 << USBB_UESTA_NBUSYBK_SHIFT)
+# define USBB_UESTA_NBUSYBK_NONE (0 << USBB_UESTA_NBUSYBK_SHIFT) /* 0 (all banks free) */
+# define USBB_UESTA_NBUSYBK_1BANK (1 << USBB_UESTA_NBUSYBK_SHIFT) /* 1 */
+# define USBB_UESTA_NBUSYBK_2BANKS (2 << USBB_UESTA_NBUSYBK_SHIFT) /* 2 */
+# define USBB_UESTA_NBUSYBK_3BANKS (3 << USBB_UESTA_NBUSYBK_SHIFT) /* 3 */
+#define USBB_UESTA_CURRBK_SHIFT (14) /* Bits 14-15: Current Bank */
+#define USBB_UESTA_CURRBK_MASK (3 << USBB_UESTA_CURRBK_SHIFT)
+# define USBB_UESTA_CURRBK_BANK0 (0 << USBB_UESTA_CURRBK_SHIFT) /* Bank0 */
+# define USBB_UESTA_CURRBK_BANK1 (1 << USBB_UESTA_CURRBK_SHIFT) /* Bank1 */
+# define USBB_UESTA_CURRBK_BANK2 (2 << USBB_UESTA_CURRBK_SHIFT) /* Bank2 */
+#define USBB_UESTA_RWALL (1 << 16) /* Bit 16: Read/Write Allowed */
+#define USBB_UESTA_CTRLDIR (1 << 17) /* Bit 17: Control Direction */
+#define USBB_UESTA_CFGOK (1 << 18) /* Bit 18: Configuration OK Status */
+#define USBB_UESTA_BYCT_SHIFT (20) /* Bits 20-30: Byte Count */
+#define USBB_UESTA_BYCT_MASK (0x7ff << USBB_UESTA_BYCT_SHIFT)
+
+/* Endpoint Status Set Register Bit-field Definitions (only in UESTASET) */
+
+#define USBB_UESTASET_NBUSYBKS (1 << 12) /* Bit 12 */
+
+/* Endpoint Control Register Bit-field Definitions */
+/* Endpoint Control Set Register Bit-field Definitions */
+/* Endpoint Control Clear Register Bit-field Definitions */
+
+#define USBB_UECON_TXINE (1 << 0) /* Bit 0: Transmitted IN Data Interrupt Enable */
+#define USBB_UECON_RXOUTE (1 << 1) /* Bit 1: Received OUT Data Interrupt Enable */
+#define USBB_UECON_RXSTPE (1 << 2) /* Bit 2: Received SETUP Interrupt Enable */
+#define USBB_UECON_UNDERFE (1 << 2) /* Bit 2: Underflow Interrupt Enable */
+#define USBB_UECON_NAKOUTE (1 << 3) /* Bit 3: NAKed OUT Interrupt Enable */
+#define USBB_UECON_NAKINE (1 << 4) /* Bit 4: NAKed IN Interrupt Enable */
+#define USBB_UECON_OVERFE (1 << 5) /* Bit 5: Overflow Interrupt Enable */
+#define USBB_UECON_STALLEDE (1 << 6) /* Bit 6: STALLed Interrupt Enable */
+#define USBB_UECON_CRCERRE (1 << 6) /* Bit 6: CRC Error Interrupt Enable */
+#define USBB_UECON_SHORTPACKETE (1 << 7) /* Bit 7: Short Packet Interrupt Enable */
+#define USBB_UECON_NBUSYBKE (1 << 12) /* Bit 12: Number of Busy Banks Interrupt Enable */
+#define USBB_UECON_KILLBK (1 << 13) /* Bit 13: Kill IN Bank (SET only) */
+#define USBB_UECON_FIFOCON (1 << 14) /* Bit 14: FIFO Control (CLR only) */
+#define USBB_UECON_EPDISHDMA (1 << 16) /* Bit 16: Endpoint Interrupts Disable HDMA Request Enable */
+#define USBB_UECON_RSTDT (1 << 18) /* Bit 18: Reset Data Toggle (SET only) */
+#define USBB_UECON_STALLRQ (1 << 19) /* Bit 19: STALL Request */
+
+/* Device DMA Channel Next Descriptor Address Register Bit-field Definitions */
+
+#define UDDMA_NEXTDESC_MASK (0xfffffff0)
+
+/* Device DMA Channel HSB Address Register Bit-field Definitions */
+/* This register holds a 32-bit address with internal bit fields */
+
+/* Device DMA Channel Control Register Bit-field Definitions */
+
+#define UDDMA_CTRL_CHEN (1 << 0) /* Bit 0: Channel Enable */
+#define UDDMA_CTRL_LDNXTCHDESCEN (1 << 1) /* Bit 1: Load Next Channel Descriptor Enable */
+#define UDDMA_CTRL_BUFFCLOSEINEN (1 << 2) /* Bit 2: Buffer Close Input Enable */
+#define UDDMA_CTRL_DMAENDEN (1 << 3) /* Bit 3: End of DMA Buffer Output Enable */
+#define UDDMA_CTRL_EOTIRQEN (1 << 4) /* Bit 4: End of USB Transfer Interrupt Enable */
+#define UDDMA_CTRL_EOBUFFIRQEN (1 << 5) /* Bit 5: End of Buffer Interrupt Enable */
+#define UDDMA_CTRL_DESCLDIRQEN (1 << 6) /* Bit 6: Descriptor Loaded Interrupt Enable */
+#define UDDMA_CTRL_BURSTLOCKEN (1 << 7) /* Bit 7: Burst Lock Enable */
+#define UDDMA_CTRL_CHBYTELENGTH_SHIFT (16) /* Bits 16-31: Channel Byte Length */
+#define UDDMA_CTRL_CHBYTELENGTH_MASK (0xffff << UDDMA_CTRL_CHBYTELENGTH_SHIFT)
+
+/* Device DMA Channel Status Register Bit-field Definitions */
+
+#define UDDMA_STATUS_CHEN (1 << 0) /* Bit 0: Channel Enabled */
+#define UDDMA_STATUS_CHACTIVE (1 << 1) /* Bit 1: Channel Active */
+#define UDDMA_STATUS_EOTSTA (1 << 4) /* Bit 4: End of USB Transfer Status */
+#define UDDMA_STATUS_EOCHBUFFSTA (1 << 5) /* Bit 5: End of Channel Buffer Status */
+#define UDDMA_STATUS_DESCLDSTA (1 << 6) /* Bit 6: Descriptor Loaded Status */
+#define UDDMA_STATUS_CHBYTECNT_SHIFT (16) /* Bits 16-31: Channel Byte Count */
+#define UDDMA_STATUS_CHBYTECNT_MASK (0xffff << UDDMA_STATUS_CHBYTECNT_SHIFT)
+
+/* USB Host Registers Bit-field Definitions *********************************/
+
+/* Host General Control Register Bit-field Definitions */
+
+#define USBB_UHCON_SOFE (1 << 8) /* Bit 8: Start of Frame Generation Enable */
+#define USBB_UHCON_RESET (1 << 9) /* Bit 9: Send USB Reset */
+#define USBB_UHCON_RESUME (1 << 10) /* Bit 10: Send USB Resume */
+
+/* Host Global Interrupt Register Bit-field Definitions */
+/* Host Global Interrupt Clear Register Bit-field Definitions (Except as noted 1) */
+/* Host Global Interrupt Set Register Bit-field Definitions (Except as noted 2) */
+/* Host Global Interrupt Enable Register Bit-field Definitions */
+/* Host Global Interrupt Enable Clear Register Bit-field Definitions */
+/* Host Global Interrupt Enable Set Register Bit-field Definitions */
+
+#define USBB_UHINT_DCONNI (1 << 0) /* Bit 0: Device Connection Interrupt (1) */
+#define USBB_UHINT_DDISCI (1 << 1) /* Bit 1: Device Disconnection Interrupt (1) */
+#define USBB_UHINT_RSTI (1 << 2) /* Bit 2: USB Reset Sent Interrupt (1) */
+#define USBB_UHINT_RSMEDI (1 << 3) /* Bit 3: Downstream Resume Sent Interrupt (1) */
+#define USBB_UHINT_RXRSMI (1 << 4) /* Bit 4: Upstream Resume Received Interrupt (1) */
+#define USBB_UHINT_HSOFI (1 << 5) /* Bit 5: Host Start of Frame Interrupt (1) */
+#define USBB_UHINT_HWUPI (1 << 6) /* Bit 6: Host Wake-Up Interrupt (1) */
+#define USBB_UHINT_PINT(n) (1 << ((n)+8))
+#define USBB_UHINT_P0INT (1 << 8) /* Bit 8: Pipe 0 Interrupt (1,2) */
+#define USBB_UHINT_P1INT (1 << 9) /* Bit 9: Pipe 1 Interrupt (1,2) */
+#define USBB_UHINT_P2INT (1 << 10) /* Bit 10: Pipe 2 Interrupt (1,2) */
+#define USBB_UHINT_P3INT (1 << 11) /* Bit 11: Pipe 3 Interrupt (1,2) */
+#define USBB_UHINT_P4INT (1 << 12) /* Bit 12: Pipe 4 Interrupt (1,2) */
+#define USBB_UHINT_P5INT (1 << 13) /* Bit 13: Pipe 5 Interrupt (1,2) */
+#define USBB_UHINT_P6INT (1 << 14) /* Bit 14: Pipe 6 Interrupt (1,2) */
+#define USBB_UHINT_DMAINT(n) (1 << ((n)+24))
+#define USBB_UHINT_DMAINT1 (1 << 25) /* Bit 25: DMA Channel 1 Interrupt */
+#define USBB_UHINT_DMAINT2 (1 << 26) /* Bit 26: DMA Channel 2 Interrupt */
+#define USBB_UHINT_DMAINT3 (1 << 27) /* Bit 27: DMA Channel 3 Interrupt */
+#define USBB_UHINT_DMAINT4 (1 << 28) /* Bit 28: DMA Channel 4 Interrupt */
+#define USBB_UHINT_DMAINT5 (1 << 29) /* Bit 29: DMA Channel 5 Interrupt */
+#define USBB_UHINT_DMAINT6 (1 << 30) /* Bit 30: DMA Channel 6 Interrupt */
+
+/* Pipe Enable/Reset Register Bit-field Definitions */
+
+#define USBB_UPRST_PEN(n) (1 << (n))
+#define USBB_UPRST_PEN0 (1 << 0) /* Bit 0: Pipe 0 Enable */
+#define USBB_UPRST_PEN1 (1 << 1) /* Bit 1: Pipe 1 Enable */
+#define USBB_UPRST_PEN2 (1 << 2) /* Bit 2: Pipe 2 Enable */
+#define USBB_UPRST_PEN3 (1 << 3) /* Bit 3: Pipe 3 Enable */
+#define USBB_UPRST_PEN4 (1 << 4) /* Bit 4: Pipe 4 Enable */
+#define USBB_UPRST_PEN5 (1 << 5) /* Bit 5: Pipe 5 Enable */
+#define USBB_UPRST_PEN6 (1 << 6) /* Bit 6: Pipe 6 Enable */
+#define USBB_UPRST_PRST(n) (1 << ((n)+16))
+#define USBB_UPRST_PRST0 (1 << 16) /* Bit 16: Pipe 0 Reset */
+#define USBB_UPRST_PRST1 (1 << 17) /* Bit 17: Pipe 1 Reset */
+#define USBB_UPRST_PRST2 (1 << 18) /* Bit 18: Pipe 2 Reset */
+#define USBB_UPRST_PRST3 (1 << 19) /* Bit 19: Pipe 3 Reset */
+#define USBB_UPRST_PRST4 (1 << 20) /* Bit 20: Pipe 4 Reset */
+#define USBB_UPRST_PRST5 (1 << 21) /* Bit 21: Pipe 5 Reset */
+#define USBB_UPRST_PRST6 (1 << 22) /* Bit 22: Pipe 6 Reset */
+
+/* Host Frame Number Register Bit-field Definitions */
+
+#define USBB_UHFNUM_FNUM_SHIFT (3) /* Bits 3-13: Frame Number */
+#define USBB_UHFNUM_FNUM_MASK (0x7ff << USBB_UHFNUM_FNUM_SHIFT)
+#define USBB_UHFNUM_FLENHIGH_SHIFT (16) /* Bits 16-23: Frame Length */
+#define USBB_UHFNUM_FLENHIGH_MASK (0xff << USBB_UHFNUM_FLENHIGH_SHIFT)
+
+/* Host Address 1 Register Bit-field Definitions */
+
+#define USBB_UHADDR1_UHADDRP0_SHIFT (0) /* Bits 0-6: USB Host Address (Pipe 0) */
+#define USBB_UHADDR1_UHADDRP0_MASK (0x7f << USBB_UHADDR1_UHADDRP0_SHIFT)
+#define USBB_UHADDR1_UHADDRP1_SHIFT (8) /* Bits 8-14: USB Host Address (Pipe 1) */
+#define USBB_UHADDR1_UHADDRP1_MASK (0x7f << USBB_UHADDR1_UHADDRP1_SHIFT)
+#define USBB_UHADDR1_UHADDRP2_SHIFT (16) /* Bits 16-22: USB Host Address (Pipe 2) */
+#define USBB_UHADDR1_UHADDRP2_MASK (0x7f << USBB_UHADDR1_UHADDRP2_SHIFT)
+#define USBB_UHADDR1_UHADDRP3_SHIFT (24) /* Bits 24-30: USB Host Address (Pipe 3) */
+#define USBB_UHADDR1_UHADDRP3_MASK (0x7f << USBB_UHADDR1_UHADDRP3_SHIFT)
+
+/* Host Address 2 Register Bit-field Definitions */
+
+#define USBB_UHADDR2_UHADDRP4_SHIFT (0) /* Bits 0-6: USB Host Address (Pipe 4) */
+#define USBB_UHADDR2_UHADDRP4_MASK (0x7f << USBB_UHADDR1_UHADDRP4_SHIFT)
+#define USBB_UHADDR2_UHADDRP5_SHIFT (8) /* Bits 8-14: USB Host Address (Pipe 5) */
+#define USBB_UHADDR2_UHADDRP5_MASK (0x7f << USBB_UHADDR1_UHADDRP5_SHIFT)
+#define USBB_UHADDR2_UHADDRP6_SHIFT (16) /* Bits 16-22: USB Host Address (Pipe 6) */
+#define USBB_UHADDR2_UHADDRP6_MASK (0x7f << USBB_UHADDR1_UHADDRP6_SHIFT)
+#
+/* Pipe Configuration Register Bit-field Definitions */
+
+#define USBB_UPCFG_ALLOC (1 << 1) /* Bit 1: Pipe Memory Allocate */
+#define USBB_UPCFG_PBK_SHIFT (2) /* Bits 2-3: Pipe Banks */
+#define USBB_UPCFG_PBK_MASK (3 << USBB_UPCFG_PBK_SHIFT)
+# define USBB_UPCFG_PBK_1 (0 << USBB_UPCFG_PBK_SHIFT) /* 1 (single-bank pipe) */
+# define USBB_UPCFG_PBK_2 (1 << USBB_UPCFG_PBK_SHIFT) /* 2 (double-bank pipe) */
+# define USBB_UPCFG_PBK_3 (2 << USBB_UPCFG_PBK_SHIFT) /* 3 (triple-bank pipe) */
+#define USBB_UPCFG_PSIZE_SHIFT (4) /* Bits 4-6: Pipe Size */
+#define USBB_UPCFG_PSIZE_MASK (7 << USBB_UPCFG_PSIZE_SHIFT)
+# define USBB_UPCFG_PSIZE_8 (0 << USBB_UPCFG_PSIZE_SHIFT) /* 8 bytes */
+# define USBB_UPCFG_PSIZE_16 (1 << USBB_UPCFG_PSIZE_SHIFT) /* 16 bytes */
+# define USBB_UPCFG_PSIZE_32 (2 << USBB_UPCFG_PSIZE_SHIFT) /* 32 bytes */
+# define USBB_UPCFG_PSIZE_64 (3 << USBB_UPCFG_PSIZE_SHIFT) /* 64 bytes */
+# define USBB_UPCFG_PSIZE_128 (4 << USBB_UPCFG_PSIZE_SHIFT) /* 128 bytes */
+# define USBB_UPCFG_PSIZE_256 (5 << USBB_UPCFG_PSIZE_SHIFT) /* 256 bytes */
+# define USBB_UPCFG_PSIZE_512 (6 << USBB_UPCFG_PSIZE_SHIFT) /* 512 bytes */
+# define USBB_UPCFG_PSIZE_1024 (7 << USBB_UPCFG_PSIZE_SHIFT) /* 1024 bytes */
+#define USBB_UPCFG_PTOKEN_SHIFT (8) /* Bits 8-9: Pipe Token */
+#define USBB_UPCFG_PTOKEN_MASK (3 << USBB_UPCFG_PTOKEN_SHIFT)
+# define USBB_UPCFG_PTOKEN_SETUP (0 << USBB_UPCFG_PTOKEN_SHIFT) /* SETUP */
+# define USBB_UPCFG_PTOKEN_IN (1 << USBB_UPCFG_PTOKEN_SHIFT) /* IN */
+# define USBB_UPCFG_PTOKEN_OUT (2 << USBB_UPCFG_PTOKEN_SHIFT) /* OUT */
+#define USBB_UPCFG_AUTOSW (1 << 10) /* Bit 10: Automatic Switch */
+#define USBB_UPCFG_PTYPE_SHIFT (11) /* Bits 11-12: Pipe Type */
+#define USBB_UPCFG_PTYPE_MASK (3 << USBB_UPCFG_PTYPE_SHIFT)
+# define USBB_UPCFG_PTYPE_CTRL (0 << USBB_UPCFG_PTYPE_SHIFT) /* Control */
+# define USBB_UPCFG_PTYPE_ISOC (1 << USBB_UPCFG_PTYPE_SHIFT) /* Isochronous */
+# define USBB_UPCFG_PTYPE_BULK (2 << USBB_UPCFG_PTYPE_SHIFT) /* Bulk */
+# define USBB_UPCFG_PTYPE_INTR (3 << USBB_UPCFG_PTYPE_SHIFT) /* Interrupt */
+#define USBB_UPCFG_PEPNUM_SHIFT (16) /* Bits 16-19: Pipe Endpoint Number */
+#define USBB_UPCFG_PEPNUM_MASK (15 << USBB_UPCFG_PEPNUM_SHIFT)
+#define USBB_UPCFG_INTFRQ_SHIFT (24) /* Bits 24-31: Pipe Interrupt Request Frequency */
+#define USBB_UPCFG_INTFRQ_MASK (0xff << USBB_UPCFG_INTFRQ_SHIFT)
+
+/* Pipe Status Register Bit-field Definitions (common) */
+/* Pipe Status Clear Register Bit-field Definitions (common) */
+/* Pipe Status Set Register Bit-field Definitions (common) */
+
+#define USBB_UPSTA_RXINI (1 << 0) /* Bit 0: Received IN Data Interrupt */
+#define USBB_UPSTA_TXOUTI (1 << 1) /* Bit 1: Transmitted OUT Data Interrupt */
+#define USBB_UPSTA_TXSTPI (1 << 2) /* Bit 2: Transmitted SETUP Interrupt */
+#define USBB_UPSTA_UNDERFI (1 << 2) /* Bit 2: Underflow Interrupt */
+#define USBB_UPSTA_PERRI (1 << 3) /* Bit 3: Pipe Error Interrupt */
+#define USBB_UPSTA_NAKEDI (1 << 4) /* Bit 4: NAKed Interrupt */
+#define USBB_UPSTA_OVERFI (1 << 5) /* Bit 5: Overflow Interrupt */
+#define USBB_UPSTA_RXSTALLDI (1 << 6) /* Bit 6: Received STALLed Interrupt */
+#define USBB_UPSTA_CRCERRI (1 << 6) /* Bit 6: CRC Error Interrupt */
+#define USBB_UPSTA_SHORTPACKET (1 << 7) /* Bit 7: Short Packet Interrupt */
+
+/* Pipe Status Register Bit-field Definitions (only in UPSTA) */
+
+#define USBB_UPSTA_DTSEQ_SHIFT (8) /* Bits 8-9: Data Toggle Sequence */
+#define USBB_UPSTA_DTSEQ_MASK (3 << USBB_UPSTA_DTSEQ_SHIFT)
+# define USBB_UPSTA_DTSEQ_DATA0 (0 << USBB_UPSTA_DTSEQ_SHIFT) /* Data0 */
+# define USBB_UPSTA_DTSEQ_DATA1 (1 << USBB_UPSTA_DTSEQ_SHIFT) /* Data1 */
+#define USBB_UPSTA_NBUSYBK_SHIFT (12) /* Bits 12-13: Number of Busy Banks */
+#define USBB_UPSTA_NBUSYBK_MASK (3 << USBB_UPSTA_NBUSYBK_SHIFT)
+# define USBB_UPSTA_NBUSYBK_NONE (0 << USBB_UPSTA_NBUSYBK_SHIFT) /* 0 (all banks free) */
+# define USBB_UPSTA_NBUSYBK_1BANK (1 << USBB_UPSTA_NBUSYBK_SHIFT) /* 1 */
+# define USBB_UPSTA_NBUSYBK_2BANKS (2 << USBB_UPSTA_NBUSYBK_SHIFT) /* 2 */
+#define USBB_UPSTA_CURRBK_SHIFT (14) /* Bits 14-15: Current Bank */
+#define USBB_UPSTA_CURRBK_MASK (3 << USBB_UPSTA_CURRBK_SHIFT)
+# define USBB_UPSTA_CURRBK_BANK0 (0 << USBB_UPSTA_CURRBK_SHIFT) /* Bank0 */
+# define USBB_UPSTA_CURRBK_BANK1 (1 << USBB_UPSTA_CURRBK_SHIFT) /* Bank1 */
+# define USBB_UPSTA_CURRBK_BANK2 (2 << USBB_UPSTA_CURRBK_SHIFT) /* Bank2 */
+#define USBB_UPSTA_RWALL (1 << 16) /* Bit 16: Read/Write Allowed */
+#define USBB_UPSTA_CFGOK (1 << 18) /* Bit 18: Configuration OK Status */
+#define USBB_UPSTA_PBYCT_SHIFT (20) /* Bits 20-30: Pipe Byte Count */
+#define USBB_UPSTA_PBYCT_MASK (0x7ff << USBB_UPSTA_BYCT_SHIFT)
+
+/* Pipe Status Set Register Bit-field Definitions (only in UPSTASET) */
+
+#define USBB_UPSTASET_NBUSYBKS (1 << 12) /* Bit 12 */
+
+/* Pipe Control Register Bit-field Definitions */
+/* Pipe Control Clear Register Bit-field Definitions (except as noted 1) */
+/* Pipe Control Set Register Bit-field Definitions (except as noted 2) */
+
+#define USBB_UPCON_RXINE (1 << 0) /* Bit 0: Received IN Data Interrupt Enable */
+#define USBB_UPCON_TXOUTE (1 << 1) /* Bit 1: Transmitted OUT Data Interrupt Enable */
+#define USBB_UPCON_TXSTPE (1 << 2) /* Bit 2: Transmitted SETUP Interrupt Enable */
+#define USBB_UPCON_UNDERFIE (1 << 2) /* Bit 2: Underflow Interrupt Enable */
+#define USBB_UPCON_PERRE (1 << 3) /* Bit 3: Pipe Error Interrupt Enable */
+#define USBB_UPCON_NAKEDE (1 << 4) /* Bit 4: NAKed Interrupt Enable */
+#define USBB_UPCON_OVERFIE (1 << 5) /* Bit 5: Overflow Interrupt Enable */
+#define USBB_UPCON_RXSTALLDE (1 << 6) /* Bit 6: Received STALLed Interrupt Enable */
+#define USBB_UPCON_CRCERRE (1 << 6) /* Bit 6: CRC Error Interrupt Enable */
+#define USBB_UPCON_SHORTPACKETIE (1 << 7) /* Bit 7: Short Packet Interrupt Enable */
+#define USBB_UPCON_NBUSYBKE (1 << 12) /* Bit 12: Number of Busy Banks Interrupt Enable */
+#define USBB_UPCON_FIFOCON (1 << 14) /* Bit 14: FIFO Control (2) */
+#define USBB_UPCON_PDISHDMA (1 << 16) /* Bit 16: Pipe Interrupts Disable HDMA Request Enable */
+#define USBB_UPCON_PFREEZE (1 << 17) /* Bit 17: Pipe Freeze */
+#define USBB_UPCON_RSTDT (1 << 18) /* Bit 18: Reset Data Toggle (1) */
+
+/* Pipe IN Request Register Bit-field Definitions */
+
+#define USBB_UPINRQ_INRQ_SHIFT (0) /* Bits 0-7: IN Request Number before Freeze */
+#define USBB_UPINRQ_INRQ_MASK (0xff << USBB_UPINRQ_INRQ_SHIFT)
+#define USBB_UPINRQ_INMODE (1 << 8) /* Bit 8: IN Request Mode */
+
+/* Pipe Error Register Bit-field Definitions */
+
+#define USBB_UPERR_DATATGL (1 << 0) /* Bit 0: Data Toggle Error */
+#define USBB_UPERR_DATAPID (1 << 1) /* Bit 1: Data PID Error */
+#define USBB_UPERR_PID (1 << 2) /* Bit 2: PID Error */
+#define USBB_UPERR_TIMEOUT (1 << 3) /* Bit 3: Time-Out Error */
+#define USBB_UPERR_CRC16 (1 << 4) /* Bit 4: CRC16 Error */
+#define USBB_UPERR_COUNTER_SHIFT (5) /* Bits 5-6: Error Counter */
+#define USBB_UPERR_COUNTER_MASK (3 << USBB_UPERR_COUNTER_SHIFT)
+
+/* Host DMA Channel Next Descriptor Address Register Bit-field Definitions */
+
+#define UHDMA_NEXTDESC_MASK (0xfffffff0)
+
+/* Host DMA Channel HSB Address Register Bit-field Definitions */
+/* This register holds a 32-bit address with internal bit fields */
+
+/* Host DMA Channel Control Register Bit-field Definitions */
+
+#define UHDMA_CTRL_CHEN (1 << 0) /* Bit 0: Channel Enable */
+#define UHDMA_CTRL_LDNXTCHDESCEN (1 << 1) /* Bit 1: Load Next Channel Descriptor Enable */
+#define UHDMA_CTRL_BUFFCLOSEINEN (1 << 2) /* Bit 2: Buffer Close Input Enable */
+#define UHDMA_CTRL_DMAENDEN (1 << 3) /* Bit 3: End of DMA Buffer Output Enable */
+#define UHDMA_CTRL_EOTIRQEN (1 << 4) /* Bit 4: End of USB Transfer Interrupt Enable */
+#define UHDMA_CTRL_EOBUFFIRQEN (1 << 5) /* Bit 5: End of Buffer Interrupt Enable */
+#define UHDMA_CTRL_DESCLDIRQEN (1 << 6) /* Bit 6: Descriptor Loaded Interrupt Enable */
+#define UHDMA_CTRL_BURSTLOCKEN (1 << 7) /* Bit 7: Burst Lock Enable */
+#define UHDMA_CTRL_CHBYTELENGTH_SHIFT (16) /* Bits 16-31: Channel Byte Length */
+#define UHDMA_CTRL_CHBYTELENGTH_MASK (0xffff << UHDMA_CTRL_CHBYTELENGTH_SHIFT)
+
+/* Host DMA Channel Status Register Bit-field Definitions */
+
+#define UHDMA_STATUS_CHEN (1 << 0) /* Bit 0: Channel Enabled */
+#define UHDMA_STATUS_CHACTIVE (1 << 1) /* Bit 1: Channel Active */
+#define UHDMA_STATUS_EOTSTA (1 << 4) /* Bit 4: End of USB Transfer Status */
+#define UHDMA_STATUS_EOCHBUFFSTA (1 << 5) /* Bit 5: End of Channel Buffer Status */
+#define UHDMA_STATUS_DESCLDSTA (1 << 6) /* Bit 6: Descriptor Loaded Status */
+#define UHDMA_STATUS_CHBYTECNT_SHIFT (16) /* Bits 16-31: Channel Byte Count */
+#define UHDMA_STATUS_CHBYTECNT_MASK (0xffff << UHDMA_STATUS_CHBYTECNT_SHIFT)
+
+/* USB General Registers Bit-field Definitions ******************************/
+
+/* General Control Register Bit-field Definitions */
+
+#define USBB_USBCON_IDTE (1 << 0) /* Bit 0: ID Transition Interrupt Enable */
+#define USBB_USBCON_VBUSTE (1 << 1) /* Bit 1: VBus Transition Interrupt Enable */
+#define USBB_USBCON_VBERRE (1 << 3) /* Bit 3: VBus Error Interrupt Enable */
+#define USBB_USBCON_BCERRE (1 << 4) /* Bit 4: B-Connection Error Interrupt Enable */
+#define USBB_USBCON_ROLEEXE (1 << 5) /* Bit 5: Role Exchange Interrupt Enable */
+#define USBB_USBCON_STOE (1 << 7) /* Bit 7: Suspend Time-Out Interrupt Enable */
+#define USBB_USBCON_VBUSHWC (1 << 8) /* Bit 8: VBus Hardware Control */
+#define USBB_USBCON_OTGPADE (1 << 12) /* Bit 12: OTG Pad Enable */
+#define USBB_USBCON_VBUSPO (1 << 13) /* Bit 13: VBus Polarity */
+#define USBB_USBCON_FRZCLK (1 << 14) /* Bit 14: Freeze USB Clock */
+#define USBB_USBCON_USBE (1 << 15) /* Bit 15: USBB Enable */
+#define USBB_USBCON_TIMVALUE_SHIFT (16) /* Bits 16-17: Timmer Value */
+#define USBB_USBCON_TIMVALUE_MASK (3 << USBB_USBCON_TIMVALUE_SHIFT)
+#define USBB_USBCON_TIMPAGE_SHIFT (20) /* Bits 20-21: Timer Page */
+#define USBB_USBCON_TIMPAGE_MASK (3 << USBB_USBCON_TIMPAGE_SHIFT)
+#define USBB_USBCON_UNLOCK (1 << 22) /* Bit 22: Timer Access Unlock */
+#define USBB_USBCON_UIDE (1 << 24) /* Bit 24: USB_ID Pin Enable */
+#define USBB_USBCON_UIMOD (1 << 25) /* Bit 25: USBB Mode */
+
+/* General Status Register Bit-field Definitions */
+/* General Status Clear Register Bit-field Definitions */
+/* General Status Set Register Bit-field Definitions */
+
+#define USBB_USBSTA_IDTI (1 << 0) /* Bit 0: ID Transition Interrupt */
+#define USBB_USBSTA_VBUSTI (1 << 1) /* Bit 1: VBus Transition Interrupt */
+#define USBB_USBSTA_VBERRI (1 << 3) /* Bit 3: VBus Error Interrupt */
+#define USBB_USBSTA_BCERRI (1 << 4) /* Bit 4: B-Connection Error Interrupt */
+#define USBB_USBSTA_ROLEEXI (1 << 5) /* Bit 5: Role Exchange Interrupt */
+#define USBB_USBSTA_STOI (1 << 7) /* Bit 7: Suspend Time-Out Interrupt */
+#define USBB_USBSTA_VBUSRQ (1 << 9) /* Bit 8: VBus Request */
+#define USBB_USBSTA_ID (1 << 10) /* Bit 10: USB_ID Pin State (read-only) */
+#define USBB_USBSTA_VBUS (1 << 11) /* Bit 11: VBus Level (read-only) */
+#define USBB_USBSTA_SPEED_SHIFT (12) /* Bits 12-13: Speed Status (read-only) */
+#define USBB_USBSTA_SPEED_MASK (3 << USBB_USBSTA_SPEED_SHIFT)
+# define USBB_USBSTA_SPEED_FULL (0 << USBB_USBSTA_SPEED_SHIFT) /* Full-Speed mode */
+# define USBB_USBSTA_SPEED_LOW (2 << USBB_USBSTA_SPEED_SHIFT) /* Low-Speed mode */
+
+/* IP Version Register Bit-field Definitions */
+
+#define USBB_UVERS_SHIFT (0) /* Bits 0-11: Version Number */
+#define USBB_UVERS_MASK (0xfff << USBB_UVERS_SHIFT)
+#define USBB_UVERS_VARIANT_SHIFT (16) /* Bits 16-19: Variant Number */
+#define USBB_UVERS_VARIANT_MASK (15 << USBB_UVERS_VARIANT_SHIFT)
+
+/* IP Features Register Bit-field Definitions */
+
+#define USBB_UFEAT_EPTNBRMAX_SHIFT (0) /* Bits 0-3: Maximal Number of Pipes/Endpoints */
+#define USBB_UFEAT_EPTNBRMAX_MASK (15 << USBB_UFEAT_EPTNBRMAX_SHIFT)
+# define USBB_UFEAT_EPTNBRMAX_16 (0 << USBB_UFEAT_EPTNBRMAX_SHIFT) /* 16 is a special case */
+#define USBB_UFEAT_DMACHANNBR_SHIFT (4) /* Bits 4-6: Number of DMA Channels */
+#define USBB_UFEAT_DMACHANNBR_MASK (7 << USBB_UFEAT_DMACHANNBR_SHIFT)
+#define USBB_UFEAT_DMABUFFERSZ (1 << 7) /* Bit 7: DMA Buffer Size */
+#define USBB_UFEAT_DMAWDDEPTH_SHIFT (8) /* Bits 8-11: DMA FIFO Depth in Words */
+#define USBB_UFEAT_DMAWDDEPTH_MASK (15 << USBB_UFEAT_DMAWDDEPTH_SHIFT)
+# define USBB_UFEAT_DMAWDDEPTH_16 (0 << USBB_UFEAT_DMAWDDEPTH_SHIFT) /* 16 is a special case */
+#define USBB_UFEAT_FIFOMAXSZ_SHIFT (12) /* Bits 12-14: Maximal FIFO Size */
+#define USBB_UFEAT_FIFOMAXSZ_MASK (7 << USBB_UFEAT_FIFOMAXSZ_SHIFT)
+# define USBB_UFEAT_FIFOMAXSZ_LT256 (0 << USBB_UFEAT_FIFOMAXSZ_SHIFT) /* < 256 bytes */
+# define USBB_UFEAT_FIFOMAXSZ_LT512 (1 << USBB_UFEAT_FIFOMAXSZ_SHIFT) /* < 512 bytes */
+# define USBB_UFEAT_FIFOMAXSZ_LT1K (2 << USBB_UFEAT_FIFOMAXSZ_SHIFT) /* < 1024 bytes */
+# define USBB_UFEAT_FIFOMAXSZ_LT2K (3 << USBB_UFEAT_FIFOMAXSZ_SHIFT) /* < 2048 bytes */
+# define USBB_UFEAT_FIFOMAXSZ_LT4K (4 << USBB_UFEAT_FIFOMAXSZ_SHIFT) /* < 4096 bytes */
+# define USBB_UFEAT_FIFOMAXSZ_LT8K (5 << USBB_UFEAT_FIFOMAXSZ_SHIFT) /* < 8192 bytes */
+# define USBB_UFEAT_FIFOMAXSZ_LT16K (6 << USBB_UFEAT_FIFOMAXSZ_SHIFT) /* < 16384 bytes */
+# define USBB_UFEAT_FIFOMAXSZ_GE16K (7 << USBB_UFEAT_FIFOMAXSZ_SHIFT) /* >= 16384 bytes */
+#define USBB_UFEAT_BWRDPRAM (1 << 15) /* Bit 15: DPRAM Byte-Write Capability */
+
+/* IP PB Address Size Register Bit-field Definitions */
+/* IP Name Register 1 Bit-field Definitions */
+/* IP Name Register 2 Bit-field Definitions */
+
+/* These registers contain a 32-value and, hence, have no bit fields */
+
+/* USB Finite State Machine Status Register Bit-field Definitions */
+
+#define USBB_USBFSM_MASK (15)
+# define USBB_USBFSM_A_IDLESTATE (0)
+# define USBB_USBFSM_A_WAITVRISE (1)
+# define USBB_USBFSM_A_WAITBCON (2)
+# define USBB_USBFSM_A_HOST (3)
+# define USBB_USBFSM_A_SUSPEND (4)
+# define USBB_USBFSM_A_PERIPHERAL (5)
+# define USBB_USBFSM_A_WAITVFALL (6)
+# define USBB_USBFSM_A_VBUSERR (7)
+# define USBB_USBFSM_A_WAITDISCHARGE (8)
+# define USBB_USBFSM_B_IDLE (9)
+# define USBB_USBFSM_B_PERIPHERAL (10)
+# define USBB_USBFSM_B_WAITBEGINHNP (11)
+# define USBB_USBFSM_B_WAITDISCHARGE (12)
+# define USBB_USBFSM_B_WAITACON (13)
+# define USBB_USBFSM_B_HOST (14)
+# define USBB_USBFSM_B_SRPINIT (15)
+
+/* USB HSB Memory Map ***************************************************************/
+
+#define USB_FIFO0_DATA_OFFSET 0x00000 /* Pipe/Endpoint 0 FIFO Data Register */
+#define USB_FIFO1_DATA_OFFSET 0x10000 /* Pipe/Endpoint 1 FIFO Data Register */
+#define USB_FIFO2_DATA_OFFSET 0x20000 /* Pipe/Endpoint 2 FIFO Data Register */
+#define USB_FIFO3_DATA_OFFSET 0x30000 /* Pipe/Endpoint 3 FIFO Data Register */
+#define USB_FIFO4_DATA_OFFSET 0x40000 /* Pipe/Endpoint 4 FIFO Data Register */
+#define USB_FIFO5_DATA_OFFSET 0x50000 /* Pipe/Endpoint 5 FIFO Data Register */
+#define USB_FIFO6_DATA_OFFSET 0x60000 /* Pipe/Endpoint 6 FIFO Data Register */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_AVR_SRC_AT32UC3_AT32UC3_USBB_H */
+
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_wdt.h b/nuttx/arch/avr/src/at32uc3/at32uc3_wdt.h
new file mode 100644
index 000000000..384e67265
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_wdt.h
@@ -0,0 +1,87 @@
+/************************************************************************************
+ * arch/avr/src/at32uc3/at32uc3_wdt.h
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_AVR_SRC_AT32UC3_AT32UC3_WDT_H
+#define __ARCH_AVR_SRC_AT32UC3_AT32UC3_WDT_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+
+#define AVR32_WDT_CTRL_OFFSET 0x00 /* Control Register */
+#define AVR32_WDT_CLR_OFFSET 0x04 /* Clear Register */
+
+/* Register Addresses ***************************************************************/
+
+#define AVR32_WDT_CTRL (AVR32_WDT_BASE+AVR32_WDT_CTRL_OFFSET)
+#define AVR32_WDT_CLR (AVR32_WDT_BASE+AVR32_WDT_CLR_OFFSET)
+
+/* Register Bit-field Definitions ***************************************************/
+
+/* Control Register Bit-field Definitions */
+
+#define WDT_CTRL_EN (1 << 0) /* Bit 0: WDT Enable */
+#define WDT_CTRL_PSEL_SHIFT (18) /* Bits 8-12: Prescale Select */
+#define WDT_CTRL_PSEL_MASK (0x1f << WDT_CTRL_PSEL_SHIFT)
+#define WDT_CTRL_KEY_SHIFT (24) /* Bits 24-31: Write protection key */
+#define WDT_CTRL_KEY_MASK (0xff << WDT_CTRL_KEY_SHIFT)
+
+/* Clear Register Bit-field Definitions. These registers have no bit fields: "Writing
+ * periodically any value to this field when the WDT is enabled, within the watchdog
+ * time-out period, will prevent a watchdog reset."
+ */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_AVR_SRC_AT32UC3_AT32UC3_WDT_H */
+
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3a_pinmux.h b/nuttx/arch/avr/src/at32uc3/at32uc3a_pinmux.h
new file mode 100644
index 000000000..124d056d6
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3a_pinmux.h
@@ -0,0 +1,64 @@
+/************************************************************************************
+ * arch/avr/src/at32uc3/at32uc3a_pinmux.h
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_AVR_SRC_AT32UC3_AT32UC3A_PINMUX_H
+#define __ARCH_AVR_SRC_AT32UC3_AT32UC3A_PINMUX_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+#warning "Not Implemented"
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_AVR_SRC_AT32UC3_AT32UC3_PINMUX_H */
+
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3b_pinmux.h b/nuttx/arch/avr/src/at32uc3/at32uc3b_pinmux.h
new file mode 100644
index 000000000..352af2635
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3b_pinmux.h
@@ -0,0 +1,263 @@
+/************************************************************************************
+ * arch/avr/src/at32uc3/at32uc3b_pinmux.h
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_AVR_SRC_AT32UC3_AT32UC3B_PINMUX_H
+#define __ARCH_AVR_SRC_AT32UC3_AT32UC3B_PINMUX_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* NOTES:
+ * 1. No external pins for PA28-PA31, PB0-PB11 on 48-pin packages (UC3B1).
+ * 2. Function D is available only on UC3Bx12.
+ * 3. In the cases where there are multiple alternatives (such as PINMUX_USART0_RXD_1
+ * and PINMUX_USART0_RXD_2) the correct multiplexing must be selected in the board.h
+ * file (by defining PINMUX_USART0_RXD to be INMUX_USART0_RXD_1, for example).
+ */
+
+#define PINMUX_GPIO0 (GPIO_ENABLE | GPIO_PORTA | 0)
+#define PINMUX_GPIO1 (GPIO_ENABLE | GPIO_PORTA | 1)
+#define PINMUX_GPIO2 (GPIO_ENABLE | GPIO_PORTA | 2)
+#define PINMUX_GPIO3 (GPIO_ENABLE | GPIO_PORTA | 3)
+#define PINMUX_ADC_AD0 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 3)
+#define PINMUX_PM_GCLK0 U (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 3)
+#define PINMUX_SBB_USB_ID (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 3)
+#define PINMUX_ABDAC_DATA0_1 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 3)
+#define PINMUX_GPIO4 (GPIO_ENABLE | GPIO_PORTA | 4)
+#define PINMUX_ADC_AD1 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 4)
+#define PINMUX_M_GCLK1 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 4)
+#define PINMUX_USBB_USB_VBOF_1 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 4)
+#define PINMUX_ABDAC_DATAN0_1 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 4)
+#define PINMUX_GPIO5 (GPIO_ENABLE | GPIO_PORTA | 5)
+#define PINMUX_EIC_EXTINT0 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 5)
+#define PINMUX_ADC_AD2 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 5)
+#define PINMUX_USART1_DCD_1 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 5)
+#define PINMUX_ABDAC_DATA1_1 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 5)
+#define PINMUX_GPIO6 (GPIO_ENABLE | GPIO_PORTA | 6)
+#define PINMUX_EIC_EXTINT1 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 6)
+#define PINMUX_ADC_AD3 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 6)
+#define PINMUX_USART1_DSR_1 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 6)
+#define PINMUX_ABDAC_DATAN1_1 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 6)
+#define PINMUX_GPIO7 (GPIO_ENABLE | GPIO_PORTA | 7)
+#define PINMUX_PM_PWM0 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 7)
+#define PINMUX_ADC_AD4 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 7)
+#define PINMUX_USART1_DTR_1 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 7)
+#define PINMUX_SSC_RX_FRAME_SYNC (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 7)
+#define PINMUX_GPIO8 (GPIO_ENABLE | GPIO_PORTA | 8)
+#define PINMUX_PWM_PWM1_1 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 8)
+#define PINMUX_ADC_AD5 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 8)
+#define PINMUX_USART1_RI_1 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 8)
+#define PINMUX_SSC_RX_CLOCK_1 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 8)
+#define PINMUX_GPIO9 (GPIO_ENABLE | GPIO_PORTA | 9)
+#define PINMUX_TWI_SCL (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 9)
+#define PINMUX_SPI0_NPCS2_1 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 9)
+#define PINMUX_USART1_CTS_1 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 9)
+#define PINMUX_GPIO10 (GPIO_ENABLE | GPIO_PORTA | 10)
+#define PINMUX_TWI_SDA (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 10)
+#define PINMUX_SPI0_NPCS3_1 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 10)
+#define PINMUX_USART1_RTS_1 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 10)
+#define PINMUX_GPIO11 (GPIO_ENABLE | GPIO_PORTA | 11)
+#define PINMUX_USART0_RTS (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 11)
+#define PINMUX_TC_A2_1 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 11)
+#define PINMUX_PWM_PWM0_1 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 11)
+#define PINMUX_SSC_RX_DATA_1 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 11)
+#define PINMUX_GPIO12 (GPIO_ENABLE | GPIO_PORTA | 12)
+#define PINMUX_USART0_CTS (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 12)
+#define PINMUX_TC_B2_1 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 12)
+#define PINMUX_PWM_PWM1_2 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 12)
+#define PINMUX_USART1_TXD_3 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 12)
+#define PINMUX_GPIO13 (GPIO_ENABLE | GPIO_PORTA | 13)
+#define PINMUX_EIC_NMI (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 13)
+#define PINMUX_PWM_PWM2_1 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 13)
+#define PINMUX_USART0_CLK_1 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 13)
+#define PINMUX_SSC_RX_CLOCK_2 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 13)
+#define PINMUX_GPIO14 (GPIO_ENABLE | GPIO_PORTA | 14)
+#define PINMUX_SPI0_MOSI_1 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 14)
+#define PINMUX_PWM_PWM3 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 14)
+#define PINMUX_EIC_EXTINT2 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 14)
+#define PINMUX_PM_GCLK2_1 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 14)
+#define PINMUX_GPIO15 (GPIO_ENABLE | GPIO_PORTA | 15)
+#define PINMUX_SPI0_SCK_1 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 15)
+#define PINMUX_PWM_PWM4_1 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 15)
+#define PINMUX_USART2_CLK (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 15)
+#define PINMUX_GPIO16 (GPIO_ENABLE | GPIO_PORTA | 16)
+#define PINMUX_SPI0_NPCS0_1 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 16)
+#define PINMUX_TC_CLK1_1 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 16)
+#define PINMUX_PWM_PWM4_2 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 16)
+#define PINMUX_GPIO17 (GPIO_ENABLE | GPIO_PORTA | 17)
+#define PINMUX_SPI0_NPCS1_1 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 17)
+#define PINMUX_TC_CLK2_1 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 17)
+#define PINMUX_SPI0_SCK_2 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 17)
+#define PINMUX_USART1_RXD_1 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 17)
+#define PINMUX_GPIO18 (GPIO_ENABLE | GPIO_PORTA | 18)
+#define PINMUX_USART0_RXD_1 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 18)
+#define PINMUX_PWM_PWM5 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 18)
+#define PINMUX_SPI0_MISO_1 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 18)
+#define PINMUX_SSC_RX_FRAME_SYNC_1 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 18)
+#define PINMUX_GPIO19 (GPIO_ENABLE | GPIO_PORTA | 19)
+#define PINMUX_USART0_TXD_1 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 19)
+#define PINMUX_PWM_PWM6_1 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 19)
+#define PINMUX_SPI0_MOSI_2 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 19)
+#define PINMUX_SSC_TX_CLOCK_1 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 19)
+#define PINMUX_GPIO20 (GPIO_ENABLE | GPIO_PORTA | 20)
+#define PINMUX_USART1_CLK (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 20)
+#define PINMUX_TC_CLK0_1 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 20)
+#define PINMUX_USART2_RXD_2 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 20)
+#define PINMUX_SSC_TX_DATA_1 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 20)
+#define PINMUX_GPIO21 (GPIO_ENABLE | GPIO_PORTA | 21)
+#define PINMUX_PWM_PWM2_2 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 21)
+#define PINMUX_TC_A1_1 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 21)
+#define PINMUX_USART2_TXD_1 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 21)
+#define PINMUX_SSC_TX_FRAME_SYNC_1 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 21)
+#define PINMUX_GPIO22 (GPIO_ENABLE | GPIO_PORTA | 22)
+#define PINMUX_PWM_PWM6_2 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 22)
+#define PINMUX_TC_B1_1 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 22)
+#define PINMUX_ADC_TRIGGER (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 22)
+#define PINMUX_ABDAC_DATA0_2 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 22)
+#define PINMUX_GPIO23 (GPIO_ENABLE | GPIO_PORTA | 23)
+#define PINMUX_USART1_TXD_1 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 23)
+#define PINMUX_SPI0_NPCS1_2 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 23)
+#define PINMUX_EIC_EXTINT3 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 23)
+#define PINMUX_PWM_PWM0_2 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 23)
+#define PINMUX_GPIO24 (GPIO_ENABLE | GPIO_PORTA | 24)
+#define PINMUX_USART1_RXD_2 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 24)
+#define PINMUX_SPI0_NPCS0_2 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 24)
+#define PINMUX_EIC_EXTINT4 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 24)
+#define PINMUX_PWM_PWM1_3 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 24)
+#define PINMUX_GPIO25 (GPIO_ENABLE | GPIO_PORTA | 25)
+#define PINMUX_SPI0_MISO_2 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 25)
+#define PINMUX_WM_PWM3 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 25)
+#define PINMUX_EIC_EXTINT5 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 25)
+#define PINMUX_GPIO26 (GPIO_ENABLE | GPIO_PORTA | 26)
+#define PINMUX_USBB_USB_ID (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 26)
+#define PINMUX_USART2_TXD_2 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 26)
+#define PINMUX_TC_A0_1 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 26)
+#define PINMUX_ABDAC_DATA1_2 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 26)
+#define PINMUX_GPIO27 (GPIO_ENABLE | GPIO_PORTA | 27)
+#define PINMUX_USBB_USB_VBOF_2 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 27)
+#define PINMUX_USART2_RXD_1 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 27)
+#define PINMUX_TC_B0_1 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 27)
+#define PINMUX_ABDAC_DATAN1_2 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 27)
+#define PINMUX_GPIO28 (GPIO_ENABLE | GPIO_PORTA | 28)
+#define PINMUX_USART0_CLK_2 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 28)
+#define PINMUX_PWM_PWM4_3 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 28)
+#define PINMUX_SPI0_MISO_3 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 28)
+#define PINMUX_ABDAC_DATAN0_2 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 28)
+#define PINMUX_GPIO29 (GPIO_ENABLE | GPIO_PORTA | 29)
+#define PINMUX_TC_CLK0_2 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 29)
+#define PINMUX_TC_CLK1_2 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 29)
+#define PINMUX_SPI0_MOSI_3 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 29)
+#define PINMUX_GPIO30 (GPIO_ENABLE | GPIO_PORTA | 30)
+#define PINMUX_ADC_AD6 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 30)
+#define PINMUX_EIC_SCAN0 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 30)
+#define PINMUX_PM_GCLK2_2 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 30)
+#define PINMUX_GPIO31 (GPIO_ENABLE | GPIO_PORTA | 31)
+#define PINMUX_ADC_AD7 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 31)
+#define PINMUX_EIC_SCAN1 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 31)
+#define PINMUX_PWM_PWM6_3 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 31)
+#define PINMUX_GPIO32 (GPIO_ENABLE | GPIO_PORTB | 0)
+#define PINMUX_TC_A0_2 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTB | 0)
+#define PINMUX_EIC_SCAN2 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTB | 0)
+#define PINMUX_USART2_CTS (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTB | 0)
+#define PINMUX_GPIO33 (GPIO_ENABLE | GPIO_PORTB | 1)
+#define PINMUX_TC_B0_2 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTB | 1)
+#define PINMUX_EIC_SCAN3 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTB | 1)
+#define PINMUX_USART2_RTS (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTB | 1)
+#define PINMUX_GPIO34 (GPIO_ENABLE | GPIO_PORTB | 2)
+#define PINMUX_EIC_EXTINT6 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTB | 2)
+#define PINMUX_TC_A1_2 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTB | 2)
+#define PINMUX_USART1_TXD_2 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTB | 2)
+#define PINMUX_GPIO35 (GPIO_ENABLE | GPIO_PORTB | 3)
+#define PINMUX_EIC_EXTINT7 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTB | 3)
+#define PINMUX_TC_B1_2 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTB | 3)
+#define PINMUX_USART1_RXD_3 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTB | 3)
+#define PINMUX_GPIO36 (GPIO_ENABLE | GPIO_PORTB | 4)
+#define PINMUX_USART1_CTS_2 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTB | 4)
+#define PINMUX_SPI0_NPCS3_2 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTB | 4)
+#define PINMUX_TC_CLK2_2 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTB | 4)
+#define PINMUX_GPIO37 (GPIO_ENABLE | GPIO_PORTB | 5)
+#define PINMUX_USART1_RTS_2 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTB | 5)
+#define PINMUX_SPI0_NPCS2_2 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTB | 5)
+#define PINMUX_WM_PWM5 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTB | 5)
+#define PINMUX_GPIO38 (GPIO_ENABLE | GPIO_PORTB | 6)
+#define PINMUX_SSC_RX_CLOCK_3 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTB | 6)
+#define PINMUX_USART1_DCD_2 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTB | 6)
+#define PINMUX_EIC_SCAN4 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTB | 6)
+#define PINMUX_ABDAC_DATA0_3 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTB | 6)
+#define PINMUX_GPIO39 (GPIO_ENABLE | GPIO_PORTB | 7)
+#define PINMUX_SSC_RX_DATA_2 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTB | 7)
+#define PINMUX_USART1_DSR_2 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTB | 7)
+#define PINMUX_EIC_SCAN5 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTB | 7)
+#define PINMUX_ABDAC_DATAN0_3 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTB | 7)
+#define PINMUX_GPIO40 (GPIO_ENABLE | GPIO_PORTB | 8)
+#define PINMUX_SSC_RX_FRAME_SYNC_2 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTB | 8)
+#define PINMUX_USART1_DTR_2 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTB | 8)
+#define PINMUX_EIC_SCAN6 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTB | 8)
+#define PINMUX_ABDAC_DATA1_3 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTB | 8)
+#define PINMUX_GPIO41 (GPIO_ENABLE | GPIO_PORTB | 9)
+#define PINMUX_SSC_TX_CLOCK_2 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTB | 9)
+#define PINMUX_USART1_RI_2 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTB | 9)
+#define PINMUX_EIC_SCAN7 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTB | 9)
+#define PINMUX_ABDAC_DATAN1_3 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTB | 9)
+#define PINMUX_GPIO42 (GPIO_ENABLE | GPIO_PORTB | 10)
+#define PINMUX_SSC_TX_DATA_2 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTB | 10)
+#define PINMUX_TC_A2_2 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTB | 10)
+#define PINMUX_USART0_RXD_2 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTB | 10)
+#define PINMUX_GPIO43 (GPIO_ENABLE | GPIO_PORTB | 11)
+#define PINMUX_SSC_TX_FRAME_SYNC_2 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTB | 11)
+#define PINMUX_TC_B2_2 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTB | 11)
+#define PINMUX_USART0_TXD_2 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTB | 11)
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_AVR_SRC_AT32UC3_AT32UC3B_PINMUX_H */
+
diff --git a/nuttx/arch/avr/src/at32uc3/chip.h b/nuttx/arch/avr/src/at32uc3/chip.h
new file mode 100644
index 000000000..ec2351b9c
--- /dev/null
+++ b/nuttx/arch/avr/src/at32uc3/chip.h
@@ -0,0 +1,223 @@
+/************************************************************************************
+ * arch/avr/src/at32uc3/chip.h
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_AVR_SRC_AT32UC3_CHIP_H
+#define __ARCH_AVR_SRC_AT32UC3_CHIP_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Get customizations for each supported chip */
+
+/* UC3 A0/A1 Series */
+/* UC3 A2/A3 Series */
+
+/* UC3 B0 (64-pin) / B1 (48-pin, no USB host) Series */
+
+#if CONFIG_ARCH_CHIP_AT32UC3B064
+# define CONFIG_ARCH_CHIP_AT32UC3B 1 /* UC3 B series */
+# define CONFIG_ARCH_CHIP_AT32UC3B0 1 /* UC3 B0 (64-pin) series */
+# define AVR32_ONCHIP_FLASH_SIZE (64*1024) /* Size of on-chip FLASH (bytes) */
+# define AVR32_ONCHIP_SRAM_SIZE (16*1024) /* Size of on-chip SRAM (bytes) */
+# define AVR32_USB_FULLSPEED 1 /* USB full-speed support */
+# define AVR32_USB_HOST 1 /* USB host support (OTG) */
+# define AVR32_USB_DEVICE 1 /* USB device support */
+# define AVR32_NUSART 3 /* Number of USARTs */
+# define AVR32_NSPI 2 /* Number of SPI */
+# define AVR32_NTWI 1 /* Number of TWI (I2C) */
+# define AVR32_NSSC 1 /* Number of SSC (I2S audio) */
+# define AVR32_NGPIO 44 /* Number of GPIO pins */
+# define AVR32_NTIMER 3 /* Number of Timers */
+# define AVR32_NPWM 13 /* Number of PWM channels */
+# define AVR32_NOSC 2 /* Number of crystal oscillators */
+# define AVR32_NADC10 8 /* Number of 10-bit A/D channels */
+# define AVR32_NDMAC 7 /* Number of DMA channels */
+#elif CONFIG_ARCH_CHIP_AT32UC3B0128
+# define CONFIG_ARCH_CHIP_AT32UC3B 1 /* UC3 B series */
+# define CONFIG_ARCH_CHIP_AT32UC3B0 1 /* UC3 B0 (64-pin) series */
+# define AVR32_ONCHIP_FLASH_SIZE (128*1024) /* Size of on-chip FLASH (bytes) */
+# define AVR32_ONCHIP_SRAM_SIZE (32*1024) /* Size of on-chip SRAM (bytes) */
+# define AVR32_USB_FULLSPEED 1 /* USB full-speed support */
+# define AVR32_USB_HOST 1 /* USB host support (OTG) */
+# define AVR32_USB_DEVICE 1 /* USB device support */
+# define AVR32_NUSART 3 /* Number of USARTs */
+# define AVR32_NSPI 2 /* Number of SPI */
+# define AVR32_NTWI 1 /* Number of TWI (I2C) */
+# define AVR32_NSSC 1 /* Number of SSC (I2S audio) */
+# define AVR32_NGPIO 44 /* Number of GPIO pins */
+# define AVR32_NTIMER 3 /* Number of Timers */
+# define AVR32_NPWM 13 /* Number of PWM channels */
+# define AVR32_NOSC 2 /* Number of crystal oscillators */
+# define AVR32_NADC10 8 /* Number of 10-bit A/D channels */
+# define AVR32_NDMAC 7 /* Number of DMA channels */
+#elif CONFIG_ARCH_CHIP_AT32UC3B0256
+# define CONFIG_ARCH_CHIP_AT32UC3B 1 /* UC3 B series */
+# define CONFIG_ARCH_CHIP_AT32UC3B0 1 /* UC3 B0 (64-pin) series */
+# define AVR32_ONCHIP_FLASH_SIZE (256*1024) /* Size of on-chip FLASH (bytes) */
+# define AVR32_ONCHIP_SRAM_SIZE (32*1024) /* Size of on-chip SRAM (bytes) */
+# define AVR32_USB_FULLSPEED 1 /* USB full-speed support */
+# define AVR32_USB_HOST 1 /* USB host support (OTG) */
+# define AVR32_USB_DEVICE 1 /* USB device support */
+# define AVR32_NUSART 3 /* Number of USARTs */
+# define AVR32_NSPI 2 /* Number of SPI */
+# define AVR32_NTWI 1 /* Number of TWI (I2C) */
+# define AVR32_NSSC 1 /* Number of SSC (I2S audio) */
+# define AVR32_NGPIO 44 /* Number of GPIO pins */
+# define AVR32_NTIMER 3 /* Number of Timers */
+# define AVR32_NPWM 13 /* Number of PWM channels */
+# define AVR32_NOSC 2 /* Number of crystal oscillators */
+# define AVR32_NADC10 8 /* Number of 10-bit A/D channels */
+# define AVR32_NDMAC 7 /* Number of DMA channels */
+#elif CONFIG_ARCH_CHIP_AT32UC3B0512
+# define CONFIG_ARCH_CHIP_AT32UC3B 1 /* UC3 B series */
+# define CONFIG_ARCH_CHIP_AT32UC3B0 1 /* UC3 B0 (64-pin) series */
+# define AVR32_ONCHIP_FLASH_SIZE (512*1024) /* Size of on-chip FLASH (bytes) */
+# define AVR32_ONCHIP_SRAM_SIZE (96*1024) /* Size of on-chip SRAM (bytes) */
+# define AVR32_USB_FULLSPEED 1 /* USB full-speed support */
+# define AVR32_USB_HOST 1 /* USB host support (OTG) */
+# define AVR32_USB_DEVICE 1 /* USB device support */
+# define AVR32_NUSART 3 /* Number of USARTs */
+# define AVR32_NSPI 2 /* Number of SPI */
+# define AVR32_NTWI 1 /* Number of TWI (I2C) */
+# define AVR32_NSSC 1 /* Number of SSC (I2S audio) */
+# define AVR32_NGPIO 44 /* Number of GPIO pins */
+# define AVR32_NTIMER 3 /* Number of Timers */
+# define AVR32_NPWM 13 /* Number of PWM channels */
+# define AVR32_NOSC 2 /* Number of crystal oscillators */
+# define AVR32_NADC10 8 /* Number of 10-bit A/D channels */
+# define AVR32_NDMAC 7 /* Number of DMA channels */
+#elif CONFIG_ARCH_CHIP_AT32UC3B164
+# define CONFIG_ARCH_CHIP_AT32UC3B 1 /* UC3 B series */
+# define CONFIG_ARCH_CHIP_AT32UC3B1 1 /* UC3 B0 (48-pin) series */
+# define AVR32_ONCHIP_FLASH_SIZE (64*1024) /* Size of on-chip FLASH (bytes) */
+# define AVR32_ONCHIP_SRAM_SIZE (16*1024) /* Size of on-chip SRAM (bytes) */
+# define AVR32_USB_FULLSPEED 1 /* USB full-speed support */
+# undef AVR32_USB_HOST /* No USB host support */
+# define AVR32_USB_DEVICE 1 /* USB device support */
+# define AVR32_NUSART 2 /* Number of USARTs */
+# define AVR32_NSPI 2 /* Number of SPI */
+# define AVR32_NTWI 1 /* Number of TWI (I2C) */
+# define AVR32_NSSC 0 /* Number of SSC (I2S audio) */
+# define AVR32_NGPIO 28 /* Number of GPIO pins */
+# define AVR32_NTIMER 3 /* Number of Timers */
+# define AVR32_NPWM 13 /* Number of PWM channels */
+# define AVR32_NOSC 1 /* Number of crystal oscillators */
+# define AVR32_NADC10 6 /* Number of 10-bit A/D channels */
+# define AVR32_NDMAC 7 /* Number of DMA channels */
+#elif CONFIG_ARCH_CHIP_AT32UC3B1128
+# define CONFIG_ARCH_CHIP_AT32UC3B 1 /* UC3 B series */
+# define CONFIG_ARCH_CHIP_AT32UC3B1 1 /* UC3 B0 (48-pin) series */
+# define AVR32_ONCHIP_FLASH_SIZE (128*1024) /* Size of on-chip FLASH (bytes) */
+# define AVR32_ONCHIP_SRAM_SIZE (32*1024) /* Size of on-chip SRAM (bytes) */
+# define AVR32_USB_FULLSPEED 1 /* USB full-speed support */
+# undef AVR32_USB_HOST /* No USB host support */
+# define AVR32_USB_DEVICE 1 /* USB device support */
+# define AVR32_NUSART 2 /* Number of USARTs */
+# define AVR32_NSPI 2 /* Number of SPI */
+# define AVR32_NTWI 1 /* Number of TWI (I2C) */
+# define AVR32_NSSC 0 /* Number of SSC (I2S audio) */
+# define AVR32_NGPIO 28 /* Number of GPIO pins */
+# define AVR32_NTIMER 3 /* Number of Timers */
+# define AVR32_NPWM 13 /* Number of PWM channels */
+# define AVR32_NOSC 1 /* Number of crystal oscillators */
+# define AVR32_NADC10 6 /* Number of 10-bit A/D channels */
+# define AVR32_NDMAC 7 /* Number of DMA channels */
+#elif CONFIG_ARCH_CHIP_AT32UC3B1256
+# define CONFIG_ARCH_CHIP_AT32UC3B 1 /* UC3 B series */
+# define CONFIG_ARCH_CHIP_AT32UC3B1 1 /* UC3 B0 (48-pin) series */
+# define AVR32_ONCHIP_FLASH_SIZE (256*1024) /* Size of on-chip FLASH (bytes) */
+# define AVR32_ONCHIP_SRAM_SIZE (32*1024) /* Size of on-chip SRAM (bytes) */
+# define AVR32_USB_FULLSPEED 1 /* USB full-speed support */
+# undef AVR32_USB_HOST /* No USB host support */
+# define AVR32_USB_DEVICE 1 /* USB device support */
+# define AVR32_NUSART 2 /* Number of USARTs */
+# define AVR32_NSPI 2 /* Number of SPI */
+# define AVR32_NTWI 1 /* Number of TWI (I2C) */
+# define AVR32_NSSC 0 /* Number of SSC (I2S audio) */
+# define AVR32_NGPIO 28 /* Number of GPIO pins */
+# define AVR32_NTIMER 3 /* Number of Timers */
+# define AVR32_NPWM 13 /* Number of PWM channels */
+# define AVR32_NOSC 1 /* Number of crystal oscillators */
+# define AVR32_NADC10 6 /* Number of 10-bit A/D channels */
+# define AVR32_NDMAC 7 /* Number of DMA channels */
+#elif CONFIG_ARCH_CHIP_AT32UC3B1512
+# define CONFIG_ARCH_CHIP_AT32UC3B 1 /* UC3 B series */
+# define CONFIG_ARCH_CHIP_AT32UC3B1 1 /* UC3 B0 (48-pin) series */
+# define AVR32_ONCHIP_FLASH_SIZE (512*1024) /* Size of on-chip FLASH (bytes) */
+# define AVR32_ONCHIP_SRAM_SIZE (96*1024) /* Size of on-chip SRAM (bytes) */
+# define AVR32_USB_FULLSPEED 1 /* USB full-speed support */
+# undef AVR32_USB_HOST /* No USB host support */
+# define AVR32_USB_DEVICE 1 /* USB device support */
+# define AVR32_NUSART 2 /* Number of USARTs */
+# define AVR32_NSPI 2 /* Number of SPI */
+# define AVR32_NTWI 1 /* Number of TWI (I2C) */
+# define AVR32_NSSC 0 /* Number of SSC (I2S audio) */
+# define AVR32_NGPIO 28 /* Number of GPIO pins */
+# define AVR32_NTIMER 3 /* Number of Timers */
+# define AVR32_NPWM 13 /* Number of PWM channels */
+# define AVR32_NOSC 1 /* Number of crystal oscillators */
+# define AVR32_NADC10 6 /* Number of 10-bit A/D channels */
+# define AVR32_NDMAC 7 /* Number of DMA channels */
+#else
+# error "Unsupported AVR32 chip"
+#endif
+
+/* Include only the memory map. Other chip hardware files should then include this
+ * file for the proper setup
+ */
+
+#include "at32uc3_memorymap.h"
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_AVR_SRC_AT32UC3_CHIP_H */
+