summaryrefslogtreecommitdiff
path: root/nuttx/arch/avr
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2010-10-13 02:45:17 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2010-10-13 02:45:17 +0000
commit6bedd0022bd16b9e6953572e079da7b631202b8b (patch)
tree586af3dab873e6e89718c310c40fb1f6c532213b /nuttx/arch/avr
parent0318862731e53936ad76703801278e2f9ea75d9c (diff)
downloadpx4-nuttx-6bedd0022bd16b9e6953572e079da7b631202b8b.tar.gz
px4-nuttx-6bedd0022bd16b9e6953572e079da7b631202b8b.tar.bz2
px4-nuttx-6bedd0022bd16b9e6953572e079da7b631202b8b.zip
GPIO support/USART GPIO init
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3007 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/avr')
-rw-r--r--nuttx/arch/avr/src/at91uc3/at91uc3_clkinit.c5
-rwxr-xr-xnuttx/arch/avr/src/at91uc3/at91uc3_config.h4
-rw-r--r--nuttx/arch/avr/src/at91uc3/at91uc3_gpio.c193
-rwxr-xr-xnuttx/arch/avr/src/at91uc3/at91uc3_internal.h19
-rw-r--r--nuttx/arch/avr/src/at91uc3/at91uc3_lowconsole.c41
-rw-r--r--nuttx/arch/avr/src/at91uc3/at91uc3_lowinit.c3
-rwxr-xr-xnuttx/arch/avr/src/at91uc3/at91uc3b_pinmux.h387
7 files changed, 439 insertions, 213 deletions
diff --git a/nuttx/arch/avr/src/at91uc3/at91uc3_clkinit.c b/nuttx/arch/avr/src/at91uc3/at91uc3_clkinit.c
index 263fe5b23..34cf9112f 100644
--- a/nuttx/arch/avr/src/at91uc3/at91uc3_clkinit.c
+++ b/nuttx/arch/avr/src/at91uc3/at91uc3_clkinit.c
@@ -112,7 +112,7 @@ void up_clkinitialize(void)
regval |= (AVR32_OSC0STARTUP << PM_OSCCTRL_STARTUP_SHIFT);
putreg32(regval, AVR32_PM_OSCCTRL0);
- /* Enabled OSC0 */
+ /* Enable OSC0 */
regval = getreg32(AVR32_PM_MCCTRL);
regval |= PM_MCCTRL_OSC0EN;
@@ -128,6 +128,9 @@ void up_clkinitialize(void)
regval &= ~PM_MCCTRL_MCSEL_MASK;
regval |= PM_MCCTRL_MCSEL_OSC0;
putreg32(regval, AVR32_PM_MCCTRL);
+
+ /* Now, enable PLL0 */
+#warning "Missing Logic"
}
diff --git a/nuttx/arch/avr/src/at91uc3/at91uc3_config.h b/nuttx/arch/avr/src/at91uc3/at91uc3_config.h
index dbe6403ec..d33ca1f1a 100755
--- a/nuttx/arch/avr/src/at91uc3/at91uc3_config.h
+++ b/nuttx/arch/avr/src/at91uc3/at91uc3_config.h
@@ -129,11 +129,11 @@
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# define HAVE_SERIAL_CONSOLE 1
-#elif defined(CONFIG_USART1_SERIAL_CONSOLE) && defined(CONFIG_AVR32_USART10_RS232)
+#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_USART20_RS232)
+#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
diff --git a/nuttx/arch/avr/src/at91uc3/at91uc3_gpio.c b/nuttx/arch/avr/src/at91uc3/at91uc3_gpio.c
index e247a363e..82055ea84 100644
--- a/nuttx/arch/avr/src/at91uc3/at91uc3_gpio.c
+++ b/nuttx/arch/avr/src/at91uc3/at91uc3_gpio.c
@@ -39,16 +39,27 @@
#include <nuttx/config.h>
-#include <errno.h>
+#include <sys/types.h>
+#include <assert.h>
#include "at91uc3_config.h"
#include "up_internal.h"
#include "at91uc3_internal.h"
+#include "up_arch.h"
+#include "chip.h"
+#include "at91uc3_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
**************************************************************************/
@@ -65,6 +76,25 @@
* 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
**************************************************************************/
@@ -83,8 +113,117 @@
int at91uc3_configgpio(uint16_t cfgset)
{
-#warning "Not Implemented"
- return -ENOSYS;
+ 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;
}
/************************************************************************************
@@ -97,7 +236,32 @@ int at91uc3_configgpio(uint16_t cfgset)
void at91uc3_gpiowrite(uint16_t pinset, bool value)
{
-#warning "Not Implemented"
+ 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);
+ }
}
/************************************************************************************
@@ -110,6 +274,23 @@ void at91uc3_gpiowrite(uint16_t pinset, bool value)
bool at91uc3_gpioread(uint16_t pinset)
{
-#warning "Not Implemented"
- return false;
+ 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/at91uc3/at91uc3_internal.h b/nuttx/arch/avr/src/at91uc3/at91uc3_internal.h
index 3f26ef93c..bede4717f 100755
--- a/nuttx/arch/avr/src/at91uc3/at91uc3_internal.h
+++ b/nuttx/arch/avr/src/at91uc3/at91uc3_internal.h
@@ -72,6 +72,9 @@
# 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 .... .... ....
*/
@@ -102,14 +105,14 @@
*/
#define GPIO_FUNC_SHIFT (9) /* Bits 9-10: Peripheral MUX */
-#define GPIO_FUNC_MASK (3 << GPIO_MUX_SHIFT)
-# define GPIO_FUNCA (0 << GPIO_MUX_SHIFT) /* PMR0=0 PMR1=0 */
-# define GPIO_FUNCB (1 << GPIO_MUX_SHIFT) /* PMR0=1 PMR1=0 */
-# define GPIO_FUNCC (2 << GPIO_MUX_SHIFT) /* PMR0=0 PMR1=1 */
-# define GPIO_FUNCD (3 << GPIO_MUX_SHIFT) /* PMR0=1 PMR1=1 */
-
-# define GPIO_PMR0 (1 << GPIO_MUX_SHIFT)
-# define GPIO_PMR1 (2 << GPIO_MUX_SHIFT)
+#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 .... ....
diff --git a/nuttx/arch/avr/src/at91uc3/at91uc3_lowconsole.c b/nuttx/arch/avr/src/at91uc3/at91uc3_lowconsole.c
index 99345d529..0fcfb5487 100644
--- a/nuttx/arch/avr/src/at91uc3/at91uc3_lowconsole.c
+++ b/nuttx/arch/avr/src/at91uc3/at91uc3_lowconsole.c
@@ -50,6 +50,7 @@
#include "up_internal.h"
#include "at91uc3_internal.h"
#include "at91uc3_usart.h"
+#include "at91uc3_pinmux.h"
/******************************************************************************
* Private Definitions
@@ -301,10 +302,46 @@ void usart_configure(uintptr_t usart_base, uint32_t baud, unsigned int parity,
#ifndef CONFIG_USE_EARLYSERIALINIT
void up_consoleinit(void)
{
-#ifdef HAVE_SERIAL_CONSOLE
+ /* 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.
+ */
+
+ at91uc3_configgpio(PINMUX_USART0_RXD);
+ at91uc3_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.
+ */
+
+ at91uc3_configgpio(PINMUX_USART1_RXD);
+ at91uc3_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.
+ */
+
+ at91uc3_configgpio(PINMUX_USART2_RXD);
+ at91uc3_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);
-# warning "Probably not all Implemented"
#endif
}
#endif
diff --git a/nuttx/arch/avr/src/at91uc3/at91uc3_lowinit.c b/nuttx/arch/avr/src/at91uc3/at91uc3_lowinit.c
index 3c01fd85a..071e86690 100644
--- a/nuttx/arch/avr/src/at91uc3/at91uc3_lowinit.c
+++ b/nuttx/arch/avr/src/at91uc3/at91uc3_lowinit.c
@@ -89,14 +89,13 @@ void up_lowinit(void)
/* Initialize a console (probably a serial console) */
-#ifndef CONFIG_USE_EARLYSERIALINIT
up_consoleinit();
-#else
/* Perform early serial initialization (so that we will have debug output
* available as soon as possible).
*/
+#ifdef CONFIG_USE_EARLYSERIALINIT
up_earlyserialinit();
#endif
diff --git a/nuttx/arch/avr/src/at91uc3/at91uc3b_pinmux.h b/nuttx/arch/avr/src/at91uc3/at91uc3b_pinmux.h
index 2361fb9b2..ffa4cff20 100755
--- a/nuttx/arch/avr/src/at91uc3/at91uc3b_pinmux.h
+++ b/nuttx/arch/avr/src/at91uc3/at91uc3b_pinmux.h
@@ -49,200 +49,203 @@
/* 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 (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 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 4)
-#define PINMUX_ABDAC_DATAN0 (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 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 5)
-#define PINMUX_ABDAC_DATA1 (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 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 6)
-#define PINMUX_ABDAC_DATAN1 (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 (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 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 8)
-#define PINMUX_ADC_AD5 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 8)
-#define PINMUX_USART1_RI (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 8)
-#define PINMUX_SSC_RX_CLOCK (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 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 9)
-#define PINMUX_USART1_CTS (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 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 10)
-#define PINMUX_USART1_RTS (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 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 11)
-#define PINMUX_PWM_PWM0 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 11)
-#define PINMUX_SSC_RX_DATA (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 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 12)
-#define PINMUX_PWM_PWM1 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 12)
-#define PINMUX_USART1_TXD (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 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 13)
-#define PINMUX_USART0_CLK (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 13)
-#define PINMUX_SSC_RX_CLOCK (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 13)
-#define PINMUX_GPIO14 (GPIO_ENABLE | GPIO_PORTA | 14)
-#define PINMUX_SPI0_MOSI (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 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 14)
-#define PINMUX_GPIO15 (GPIO_ENABLE | GPIO_PORTA | 15)
-#define PINMUX_SPI0_SCK (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 15)
-#define PINMUX_PWM_PWM4 (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 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 16)
-#define PINMUX_TC_CLK1 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 16)
-#define PINMUX_PWM_PWM4 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 16)
-#define PINMUX_GPIO17 (GPIO_ENABLE | GPIO_PORTA | 17)
-#define PINMUX_SPI0_NPCS1 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 17)
-#define PINMUX_TC_CLK2 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 17)
-#define PINMUX_SPI0_SCK (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 17)
-#define PINMUX_USART1_RXD (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 17)
-#define PINMUX_GPIO18 (GPIO_ENABLE | GPIO_PORTA | 18)
-#define PINMUX_USART0_RXD (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 18)
-#define PINMUX_PWM_PWM5 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 18)
-#define PINMUX_SPI0_MISO (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 18)
-#define PINMUX_SSC_RX_FRAME_SYNC (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 18)
-#define PINMUX_GPIO19 (GPIO_ENABLE | GPIO_PORTA | 19)
-#define PINMUX_USART0_TXD (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 19)
-#define PINMUX_PWM_PWM6 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 19)
-#define PINMUX_SPI0_MOSI (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 19)
-#define PINMUX_SSC_TX_CLOCK (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 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 20)
-#define PINMUX_USART2_RXD (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 20)
-#define PINMUX_SSC_TX_DATA (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 20)
-#define PINMUX_GPIO21 (GPIO_ENABLE | GPIO_PORTA | 21)
-#define PINMUX_PWM_PWM2 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 21)
-#define PINMUX_TC_A1 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 21)
-#define PINMUX_USART2_TXD (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 21)
-#define PINMUX_SSC_TX_FRAME_SYNC (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 21)
-#define PINMUX_GPIO22 (GPIO_ENABLE | GPIO_PORTA | 22)
-#define PINMUX_PWM_PWM6 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 22)
-#define PINMUX_TC_B1 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 22)
-#define PINMUX_ADC_TRIGGER (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 22)
-#define PINMUX_ABDAC_DATA0 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 22)
-#define PINMUX_GPIO23 (GPIO_ENABLE | GPIO_PORTA | 23)
-#define PINMUX_USART1_TXD (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 23)
-#define PINMUX_SPI0_NPCS1 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 23)
-#define PINMUX_EIC_EXTINT3 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 23)
-#define PINMUX_PWM_PWM0 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 23)
-#define PINMUX_GPIO24 (GPIO_ENABLE | GPIO_PORTA | 24)
-#define PINMUX_USART1_RXD (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 24)
-#define PINMUX_SPI0_NPCS0 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 24)
-#define PINMUX_EIC_EXTINT4 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 24)
-#define PINMUX_PWM_PWM1 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 24)
-#define PINMUX_GPIO25 (GPIO_ENABLE | GPIO_PORTA | 25)
-#define PINMUX_SPI0_MISO (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 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 26)
-#define PINMUX_TC_A0 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 26)
-#define PINMUX_ABDAC_DATA1 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 26)
-#define PINMUX_GPIO27 (GPIO_ENABLE | GPIO_PORTA | 27)
-#define PINMUX_USBB_USB_VBOF (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 27)
-#define PINMUX_USART2_RXD (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 27)
-#define PINMUX_TC_B0 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 27)
-#define PINMUX_ABDAC_DATAN1 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 27)
-#define PINMUX_GPIO28 (GPIO_ENABLE | GPIO_PORTA | 28)
-#define PINMUX_USART0_CLK (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 28)
-#define PINMUX_PWM_PWM4 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 28)
-#define PINMUX_SPI0_MISO (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 28)
-#define PINMUX_ABDAC_DATAN0 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTA | 28)
-#define PINMUX_GPIO29 (GPIO_ENABLE | GPIO_PORTA | 29)
-#define PINMUX_TC_CLK0 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTA | 29)
-#define PINMUX_TC_CLK1 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTA | 29)
-#define PINMUX_SPI0_MOSI (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 (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 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTA | 31)
-#define PINMUX_GPIO32 (GPIO_ENABLE | GPIO_PORTB | 0)
-#define PINMUX_TC_A0 (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 (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 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTB | 2)
-#define PINMUX_USART1_TXD (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 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTB | 3)
-#define PINMUX_USART1_RXD (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTB | 3)
-#define PINMUX_GPIO36 (GPIO_ENABLE | GPIO_PORTB | 4)
-#define PINMUX_USART1_CTS (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTB | 4)
-#define PINMUX_SPI0_NPCS3 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTB | 4)
-#define PINMUX_TC_CLK2 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTB | 4)
-#define PINMUX_GPIO37 (GPIO_ENABLE | GPIO_PORTB | 5)
-#define PINMUX_USART1_RTS (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTB | 5)
-#define PINMUX_SPI0_NPCS2 (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 (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTB | 6)
-#define PINMUX_USART1_DCD (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTB | 6)
-#define PINMUX_EIC_SCAN4 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTB | 6)
-#define PINMUX_ABDAC_DATA0 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTB | 6)
-#define PINMUX_GPIO39 (GPIO_ENABLE | GPIO_PORTB | 7)
-#define PINMUX_SSC_RX_DATA (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTB | 7)
-#define PINMUX_USART1_DSR (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTB | 7)
-#define PINMUX_EIC_SCAN5 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTB | 7)
-#define PINMUX_ABDAC_DATAN0 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTB | 7)
-#define PINMUX_GPIO40 (GPIO_ENABLE | GPIO_PORTB | 8)
-#define PINMUX_SSC_RX_FRAME_SYNC (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTB | 8)
-#define PINMUX_USART1_DTR (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTB | 8)
-#define PINMUX_EIC_SCAN6 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTB | 8)
-#define PINMUX_ABDAC_DATA1 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTB | 8)
-#define PINMUX_GPIO41 (GPIO_ENABLE | GPIO_PORTB | 9)
-#define PINMUX_SSC_TX_CLOCK (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTB | 9)
-#define PINMUX_USART1_RI (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTB | 9)
-#define PINMUX_EIC_SCAN7 (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTB | 9)
-#define PINMUX_ABDAC_DATAN1 (GPIO_PERIPH | GPIO_FUNCD | GPIO_PORTB | 9)
-#define PINMUX_GPIO42 (GPIO_ENABLE | GPIO_PORTB | 10)
-#define PINMUX_SSC_TX_DATA (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTB | 10)
-#define PINMUX_TC_A2 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTB | 10)
-#define PINMUX_USART0_RXD (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTB | 10)
-#define PINMUX_PIO43 (GPIO_ENABLE | GPIO_PORTB | 11)
-#define PINMUX_SSC_TX_FRAME_SYNC (GPIO_PERIPH | GPIO_FUNCA | GPIO_PORTB | 11)
-#define PINMUX_TC_B2 (GPIO_PERIPH | GPIO_FUNCB | GPIO_PORTB | 11)
-#define PINMUX_USART0_TXD (GPIO_PERIPH | GPIO_FUNCC | GPIO_PORTB | 11)
+#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