summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-06-03 17:53:05 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-06-03 17:53:05 -0600
commit5d0aaebaa4a9bc03a1813425d4721c5550f46ba1 (patch)
tree77b8cfe1864f1a72ca5fb48aede91878243a5167
parent5cc921b5ae92b3b354b3e727743e5393607f624c (diff)
downloadpx4-nuttx-5d0aaebaa4a9bc03a1813425d4721c5550f46ba1.tar.gz
px4-nuttx-5d0aaebaa4a9bc03a1813425d4721c5550f46ba1.tar.bz2
px4-nuttx-5d0aaebaa4a9bc03a1813425d4721c5550f46ba1.zip
SAM4L alternate pin mapping header file; Use USART1 for virtual COM port console
-rw-r--r--nuttx/ChangeLog3
-rw-r--r--nuttx/arch/arm/src/sam34/chip/sam4l_pinmap.h579
-rw-r--r--nuttx/configs/sam4l-xplained/README.txt12
-rw-r--r--nuttx/configs/sam4l-xplained/include/board.h13
-rw-r--r--nuttx/configs/sam4l-xplained/ostest/defconfig24
5 files changed, 620 insertions, 11 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 5057d41df..fd94f27ba 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -4879,3 +4879,6 @@
family (2013-6-3).
* configs/sam4l-xplained: A partial configuration that will (eventually)
support the SAM4L Xplained Pro developement board (2013-6-3).
+ * arch/arm/src/sam34/chip/sam4l_pinmap.h: Initial cut as SAM4L
+ pin mapping (2013-6-3).
+
diff --git a/nuttx/arch/arm/src/sam34/chip/sam4l_pinmap.h b/nuttx/arch/arm/src/sam34/chip/sam4l_pinmap.h
new file mode 100644
index 000000000..1c6f4a481
--- /dev/null
+++ b/nuttx/arch/arm/src/sam34/chip/sam4l_pinmap.h
@@ -0,0 +1,579 @@
+/************************************************************************************
+ * arch/arm/src/sam34/chip/sam3u_pinmap.h
+ *
+ * Copyright (C) 2009-2011, 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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_ARM_SRC_SAM34_CHIP_SAM3U_PINMAP_H
+#define __ARCH_ARM_SRC_SAM34_CHIP_SAM3U_PINMAP_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+#include "sam_gpio.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+/* Alternate Pin Functions.
+ *
+ * Alternative pin selections are provided with a numeric suffix like _1, _2, etc.
+ * Drivers, however, will use the pin selection without the numeric suffix.
+ * Additional definitions are required in the board.h file. For example, if
+ * SPI MSIO connects vis PA21 on some board, then the following definition should
+ * appear in the board.h header file for that board:
+ *
+ * #define GPIO_SPI_MISO GPIO_SPI_MISO_1
+ *
+ * The driver will then automatically configre PA21 as the SPI MISO pin.
+ */
+
+/* WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!!
+ * Additional effort is required to select specific GPIO options such as frequency,
+ * open-drain/push-pull, and pull-up/down! Just the basics are defined for most
+ * pins in this file.
+ */
+
+/* Audio Bitstream DAC */
+
+#define GPIO_ABDACB_CLK_1 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN31)
+#define GPIO_ABDACB_CLK_2 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN12)
+#define GPIO_ABDACB_DAC0_1 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN17)
+#define GPIO_ABDACB_DAC0_2 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN27)
+#define GPIO_ABDACB_DAC0_3 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN2)
+#define GPIO_ABDACB_DAC0_4 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN9)
+#define GPIO_ABDACB_DAC1_1 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN19)
+#define GPIO_ABDACB_DAC1_2 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN29)
+#define GPIO_ABDACB_DAC1_3 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN4)
+#define GPIO_ABDACB_DAC1_4 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN13)
+#define GPIO_ABDACB_DACN0_1 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN18)
+#define GPIO_ABDACB_DACN0_2 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN28)
+#define GPIO_ABDACB_DACN0_3 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN3)
+#define GPIO_ABDACB_DACN0_4 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN10)
+#define GPIO_ABDACB_DACN1_1 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN20)
+#define GPIO_ABDACB_DACN1_2 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN30)
+#define GPIO_ABDACB_DACN1_3 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN5)
+#define GPIO_ABDACB_DACN1_4 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN14)
+
+/* Analog Comparator Interface */
+
+#define GPIO_ACIFC_ACAN0 (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN6)
+#define GPIO_ACIFC_ACAN1 (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN9)
+#define GPIO_ACIFC_ACAP0 (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN7)
+#define GPIO_ACIFC_ACAP1 (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN10)
+#define GPIO_ACIFC_ACBN0 (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN2)
+#define GPIO_ACIFC_ACBN1 (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN13)
+#define GPIO_ACIFC_ACBP0 (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN3)
+#define GPIO_ACIFC_ACBP1 (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN14)
+
+/* ADC controller interface */
+
+#define GPIO_ADCIFE_AD0 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN4)
+#define GPIO_ADCIFE_AD1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN5)
+#define GPIO_ADCIFE_AD2 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN7)
+#define GPIO_ADCIFE_AD3 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN2)
+#define GPIO_ADCIFE_AD4 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN3)
+#define GPIO_ADCIFE_AD5 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN4)
+#define GPIO_ADCIFE_AD6 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN5)
+#define GPIO_ADCIFE_AD7 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN7)
+#define GPIO_ADCIFE_AD8 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN8)
+#define GPIO_ADCIFE_AD9 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN9)
+#define GPIO_ADCIFE_AD10 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN10)
+#define GPIO_ADCIFE_AD11 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN11)
+#define GPIO_ADCIFE_AD12 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN12)
+#define GPIO_ADCIFE_AD13 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN13)
+#define GPIO_ADCIFE_AD14 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN14)
+#define GPIO_ADCIFE_TRIGGER (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN5)
+
+/* Capacitive Touch Module B */
+
+#define GPIO_CATB_DIS_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN12)
+#define GPIO_CATB_DIS_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN2)
+#define GPIO_CATB_DIS_3 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN23)
+#define GPIO_CATB_DIS_4 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN31)
+#define GPIO_CATB_DIS_5 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN12)
+#define GPIO_CATB_DIS_6 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN3)
+#define GPIO_CATB_DIS_7 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN14)
+#define GPIO_CATB_DIS_8 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN23)
+#define GPIO_CATB_DIS_9 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN5)
+#define GPIO_CATB_SENSE0_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN27)
+#define GPIO_CATB_SENSE0_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN4)
+#define GPIO_CATB_SENSE0_3 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN13)
+#define GPIO_CATB_SENSE1_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN28)
+#define GPIO_CATB_SENSE1_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN5)
+#define GPIO_CATB_SENSE1_3 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN14)
+#define GPIO_CATB_SENSE2_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN29)
+#define GPIO_CATB_SENSE2_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN6)
+#define GPIO_CATB_SENSE2_3 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN15)
+#define GPIO_CATB_SENSE3_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN30)
+#define GPIO_CATB_SENSE3_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN7)
+#define GPIO_CATB_SENSE3_3 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN0)
+#define GPIO_CATB_SENSE4_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN8)
+#define GPIO_CATB_SENSE4_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN1)
+#define GPIO_CATB_SENSE5_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN9)
+#define GPIO_CATB_SENSE5_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN2)
+#define GPIO_CATB_SENSE6_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN10)
+#define GPIO_CATB_SENSE6_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN3)
+#define GPIO_CATB_SENSE7_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN11)
+#define GPIO_CATB_SENSE7_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN4)
+#define GPIO_CATB_SENSE8_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN13)
+#define GPIO_CATB_SENSE8_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN6)
+#define GPIO_CATB_SENSE9_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN14)
+#define GPIO_CATB_SENSE9_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN7)
+#define GPIO_CATB_SENSE10_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN15)
+#define GPIO_CATB_SENSE10_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN8)
+#define GPIO_CATB_SENSE11_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN16)
+#define GPIO_CATB_SENSE11_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN9)
+#define GPIO_CATB_SENSE12_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN17)
+#define GPIO_CATB_SENSE12_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN10)
+#define GPIO_CATB_SENSE13_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN18)
+#define GPIO_CATB_SENSE13_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN11)
+#define GPIO_CATB_SENSE14_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN19)
+#define GPIO_CATB_SENSE14_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN12)
+#define GPIO_CATB_SENSE15_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN20)
+#define GPIO_CATB_SENSE15_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN13)
+#define GPIO_CATB_SENSE16_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN21)
+#define GPIO_CATB_SENSE16_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN15)
+#define GPIO_CATB_SENSE17_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN22)
+#define GPIO_CATB_SENSE17_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN16)
+#define GPIO_CATB_SENSE18_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN24)
+#define GPIO_CATB_SENSE18_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN17)
+#define GPIO_CATB_SENSE19_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN25)
+#define GPIO_CATB_SENSE19_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN18)
+#define GPIO_CATB_SENSE20_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN26)
+#define GPIO_CATB_SENSE20_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN19)
+#define GPIO_CATB_SENSE21_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN0)
+#define GPIO_CATB_SENSE21_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN20)
+#define GPIO_CATB_SENSE22_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN1)
+#define GPIO_CATB_SENSE22_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN21)
+#define GPIO_CATB_SENSE23_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN2)
+#define GPIO_CATB_SENSE23_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN22)
+#define GPIO_CATB_SENSE24_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN4)
+#define GPIO_CATB_SENSE24_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN24)
+#define GPIO_CATB_SENSE25_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN5)
+#define GPIO_CATB_SENSE25_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN25)
+#define GPIO_CATB_SENSE26_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN6)
+#define GPIO_CATB_SENSE26_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN26)
+#define GPIO_CATB_SENSE27_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN7)
+#define GPIO_CATB_SENSE27_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN27)
+#define GPIO_CATB_SENSE28_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN8)
+#define GPIO_CATB_SENSE28_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN28)
+#define GPIO_CATB_SENSE29_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN9)
+#define GPIO_CATB_SENSE29_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN29)
+#define GPIO_CATB_SENSE30_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN10)
+#define GPIO_CATB_SENSE30_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN30)
+#define GPIO_CATB_SENSE31_1 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN11)
+#define GPIO_CATB_SENSE31_2 (GPIO_FUNCG | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN31)
+
+/* DAC Controller */
+
+#define GPIO_DACC_EXT_TRIG0 (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN4)
+#define GPIO_DACC_VOUT (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN6)
+#define GPIO_EIC_EXTINT0 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN1)
+#define GPIO_EIC_EXTINT1_1 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN24)
+#define GPIO_EIC_EXTINT1_2 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN16)
+#define GPIO_EIC_EXTINT1_3 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN6)
+#define GPIO_EIC_EXTINT2_1 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN25)
+#define GPIO_EIC_EXTINT2_2 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN17)
+#define GPIO_EIC_EXTINT2_3 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN4)
+#define GPIO_EIC_EXTINT3_1 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN26)
+#define GPIO_EIC_EXTINT3_2 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN18)
+#define GPIO_EIC_EXTINT3_3 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN5)
+#define GPIO_EIC_EXTINT4_1 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN27)
+#define GPIO_EIC_EXTINT4_2 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN19)
+#define GPIO_EIC_EXTINT4_3 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN7)
+#define GPIO_EIC_EXTINT5_1 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN3)
+#define GPIO_EIC_EXTINT5_2 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN20)
+#define GPIO_EIC_EXTINT6_1 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN4)
+#define GPIO_EIC_EXTINT6_2 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN21)
+#define GPIO_EIC_EXTINT7_1 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN5)
+#define GPIO_EIC_EXTINT7_2 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN22)
+#define GPIO_EIC_EXTINT8_1 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN6)
+#define GPIO_EIC_EXTINT8_2 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN23)
+
+/* Glue Logic Controller */
+
+#define GPIO_GLOC_IN0_1 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN20)
+#define GPIO_GLOC_IN0_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN6)
+#define GPIO_GLOC_IN1_1 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN21)
+#define GPIO_GLOC_IN1_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN4)
+#define GPIO_GLOC_IN2_1 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN22)
+#define GPIO_GLOC_IN2_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN5)
+#define GPIO_GLOC_IN3_1 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN23)
+#define GPIO_GLOC_IN3_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN7)
+#define GPIO_GLOC_IN4_1 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN6)
+#define GPIO_GLOC_IN4_2 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN28)
+#define GPIO_GLOC_IN4_3 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN27)
+#define GPIO_GLOC_IN4_4 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN15)
+#define GPIO_GLOC_IN5_1 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN7)
+#define GPIO_GLOC_IN5_2 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN29)
+#define GPIO_GLOC_IN5_3 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN28)
+#define GPIO_GLOC_IN5_4 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN16)
+#define GPIO_GLOC_IN6_1 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN8)
+#define GPIO_GLOC_IN6_2 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN30)
+#define GPIO_GLOC_IN6_3 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN29)
+#define GPIO_GLOC_IN6_4 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN17)
+#define GPIO_GLOC_IN7_1 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN9)
+#define GPIO_GLOC_IN7_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN30)
+#define GPIO_GLOC_IN7_3 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN18)
+#define GPIO_GLOC_OUT0_1 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN24)
+#define GPIO_GLOC_OUT0_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN8)
+#define GPIO_GLOC_OUT1_1 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN10)
+#define GPIO_GLOC_OUT1_2 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN31)
+#define GPIO_GLOC_OUT1_3 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN31)
+#define GPIO_GLOC_OUT1_4 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN19)
+
+/* Inter-IC Sound (I2S) Controller */
+
+#define GPIO_IISC_IMCK_1 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN31)
+#define GPIO_IISC_IMCK_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN5)
+#define GPIO_IISC_IMCK_3 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN14)
+#define GPIO_IISC_ISCK_1 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN27)
+#define GPIO_IISC_ISCK_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN2)
+#define GPIO_IISC_ISCK_3 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN9)
+#define GPIO_IISC_ISDI_1 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN28)
+#define GPIO_IISC_ISDI_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN3)
+#define GPIO_IISC_ISDI_3 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN10)
+#define GPIO_IISC_ISDO_1 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN30)
+#define GPIO_IISC_ISDO_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN4)
+#define GPIO_IISC_ISDO_3 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN13)
+#define GPIO_IISC_IWS_1 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN29)
+#define GPIO_IISC_IWS_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN6)
+#define GPIO_IISC_IWS_3 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN12)
+
+/* LCD Controller A */
+
+#define GPIO_LCDCA_COM0 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN12)
+#define GPIO_LCDCA_COM1 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN11)
+#define GPIO_LCDCA_COM2 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN10)
+#define GPIO_LCDCA_COM3 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN9)
+#define GPIO_LCDCA_SEG0 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN15)
+#define GPIO_LCDCA_SEG1 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN16)
+#define GPIO_LCDCA_SEG2 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN17)
+#define GPIO_LCDCA_SEG3 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN18)
+#define GPIO_LCDCA_SEG4 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN19)
+#define GPIO_LCDCA_SEG5 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN13)
+#define GPIO_LCDCA_SEG6 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN14)
+#define GPIO_LCDCA_SEG7 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN15)
+#define GPIO_LCDCA_SEG8 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN16)
+#define GPIO_LCDCA_SEG9 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN17)
+#define GPIO_LCDCA_SEG10 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN20)
+#define GPIO_LCDCA_SEG11 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN21)
+#define GPIO_LCDCA_SEG12 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN22)
+#define GPIO_LCDCA_SEG13 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN23)
+#define GPIO_LCDCA_SEG14 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN8)
+#define GPIO_LCDCA_SEG15 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN9)
+#define GPIO_LCDCA_SEG16 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN10)
+#define GPIO_LCDCA_SEG17 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN11)
+#define GPIO_LCDCA_SEG18 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN18)
+#define GPIO_LCDCA_SEG19 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN19)
+#define GPIO_LCDCA_SEG20 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN20)
+#define GPIO_LCDCA_SEG21 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN7)
+#define GPIO_LCDCA_SEG22 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN6)
+#define GPIO_LCDCA_SEG23 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN8)
+#define GPIO_LCDCA_SEG24 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN24)
+#define GPIO_LCDCA_SEG25 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN25)
+#define GPIO_LCDCA_SEG26 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN26)
+#define GPIO_LCDCA_SEG27 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN27)
+#define GPIO_LCDCA_SEG28 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN28)
+#define GPIO_LCDCA_SEG29 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN29)
+#define GPIO_LCDCA_SEG30 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN30)
+#define GPIO_LCDCA_SEG31 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN31)
+#define GPIO_LCDCA_SEG32 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN12)
+#define GPIO_LCDCA_SEG33 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN13)
+#define GPIO_LCDCA_SEG34 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN21)
+#define GPIO_LCDCA_SEG35 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN22)
+#define GPIO_LCDCA_SEG36 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN14)
+#define GPIO_LCDCA_SEG37 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN15)
+#define GPIO_LCDCA_SEG38 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN23)
+#define GPIO_LCDCA_SEG39 (GPIO_FUNCF | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN24)
+
+/* Parallel Capture */
+
+#define GPIO_PARC_PCCK_1 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN17)
+#define GPIO_PARC_PCCK_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN21)
+#define GPIO_PARC_PCDATA0_1 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN9)
+#define GPIO_PARC_PCDATA0_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN24)
+#define GPIO_PARC_PCDATA1_1 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN10)
+#define GPIO_PARC_PCDATA1_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN25)
+#define GPIO_PARC_PCDATA2_1 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN11)
+#define GPIO_PARC_PCDATA2_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN26)
+#define GPIO_PARC_PCDATA3_1 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN12)
+#define GPIO_PARC_PCDATA3_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN27)
+#define GPIO_PARC_PCDATA4_1 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN13)
+#define GPIO_PARC_PCDATA4_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN28)
+#define GPIO_PARC_PCDATA5_1 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN14)
+#define GPIO_PARC_PCDATA5_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN29)
+#define GPIO_PARC_PCDATA6_1 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN15)
+#define GPIO_PARC_PCDATA6_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN30)
+#define GPIO_PARC_PCDATA7_1 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN16)
+#define GPIO_PARC_PCDATA7_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN31)
+#define GPIO_PARC_PCEN1_1 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN18)
+#define GPIO_PARC_PCEN1_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN22)
+#define GPIO_PARC_PCEN2_1 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN19)
+#define GPIO_PARC_PCEN2_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN23)
+
+/* Peripheral Event Controller */
+
+#define GPIO_PEVC_PAD_EVT0_1 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN8)
+#define GPIO_PEVC_PAD_EVT0_2 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN12)
+#define GPIO_PEVC_PAD_EVT0_3 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN24)
+#define GPIO_PEVC_PAD_EVT0_4 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN7)
+#define GPIO_PEVC_PAD_EVT1_1 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN9)
+#define GPIO_PEVC_PAD_EVT1_2 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN13)
+#define GPIO_PEVC_PAD_EVT1_3 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN25)
+#define GPIO_PEVC_PAD_EVT1_4 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN8)
+#define GPIO_PEVC_PAD_EVT2_1 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN9)
+#define GPIO_PEVC_PAD_EVT2_2 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN10)
+#define GPIO_PEVC_PAD_EVT2_3 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN11)
+#define GPIO_PEVC_PAD_EVT2_4 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN26)
+#define GPIO_PEVC_PAD_EVT3_1 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN10)
+#define GPIO_PEVC_PAD_EVT3_2 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN11)
+#define GPIO_PEVC_PAD_EVT3_3 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN27)
+
+/* System Control Interface */
+
+#define GPIO_SCIF_GCLK0_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN2)
+#define GPIO_SCIF_GCLK0_2 (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN19)
+#define GPIO_SCIF_GCLK0_3 (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN10)
+#define GPIO_SCIF_GCLK0_4 (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN26)
+#define GPIO_SCIF_GCLK1_1 (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN20)
+#define GPIO_SCIF_GCLK1_2 (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN11)
+#define GPIO_SCIF_GCLK1_3 (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN27)
+#define GPIO_SCIF_GCLK2_1 (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN12)
+#define GPIO_SCIF_GCLK2_2 (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN28)
+#define GPIO_SCIF_GCLK3_1 (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN13)
+#define GPIO_SCIF_GCLK3_2 (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN29)
+#define GPIO_SCIF_GCLK_IN0_1 (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN23)
+#define GPIO_SCIF_GCLK_IN0_2 (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN14)
+#define GPIO_SCIF_GCLK_IN0_3 (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN30)
+#define GPIO_SCIF_GCLK_IN1_1 (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN24)
+#define GPIO_SCIF_GCLK_IN1_2 (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN15)
+#define GPIO_SCIF_GCLK_IN1_3 (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN31)
+
+/* Serial Peripheral Interface */
+
+#define GPIO_SPI_MISO_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN21)
+#define GPIO_SPI_MISO_2 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN27)
+#define GPIO_SPI_MISO_3 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN4)
+#define GPIO_SPI_MISO_4 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN3)
+#define GPIO_SPI_MISO_5 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN14)
+#define GPIO_SPI_MISO_6 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN28)
+#define GPIO_SPI_MOSI_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN22)
+#define GPIO_SPI_MOSI_2 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN28)
+#define GPIO_SPI_MOSI_3 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN5)
+#define GPIO_SPI_MOSI_4 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN15)
+#define GPIO_SPI_MOSI_5 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN29)
+#define GPIO_SPI_NPCS0_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN24)
+#define GPIO_SPI_NPCS0_2 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN30)
+#define GPIO_SPI_NPCS0_3 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN3)
+#define GPIO_SPI_NPCS0_4 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN2)
+#define GPIO_SPI_NPCS0_5 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN31)
+#define GPIO_SPI_NPCS1_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN31)
+#define GPIO_SPI_NPCS1_2 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN2)
+#define GPIO_SPI_NPCS1_3 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN13)
+#define GPIO_SPI_NPCS1_4 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN13)
+#define GPIO_SPI_NPCS2_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN0)
+#define GPIO_SPI_NPCS2_2 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN11)
+#define GPIO_SPI_NPCS2_3 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN14)
+#define GPIO_SPI_NPCS3_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN1)
+#define GPIO_SPI_NPCS3_2 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN12)
+#define GPIO_SPI_NPCS3_3 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN15)
+#define GPIO_SPI_SCK_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN23)
+#define GPIO_SPI_SCK_2 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN29)
+#define GPIO_SPI_SCK_3 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN6)
+#define GPIO_SPI_SCK_4 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN30)
+
+/* Timer/Counters */
+
+#define GPIO_TC0_A0_1 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN8)
+#define GPIO_TC0_A0_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN7)
+#define GPIO_TC0_A1_1 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN10)
+#define GPIO_TC0_A1_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN9)
+#define GPIO_TC0_A2_1 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN12)
+#define GPIO_TC0_A2_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN11)
+#define GPIO_TC0_B0_1 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN9)
+#define GPIO_TC0_B0_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN8)
+#define GPIO_TC0_B1_1 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN11)
+#define GPIO_TC0_B1_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN10)
+#define GPIO_TC0_B2_1 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN13)
+#define GPIO_TC0_B2_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN12)
+#define GPIO_TC0_CLK0_1 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN14)
+#define GPIO_TC0_CLK0_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN13)
+#define GPIO_TC0_CLK1_1 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN15)
+#define GPIO_TC0_CLK1_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN14)
+#define GPIO_TC0_CLK2_1 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN16)
+#define GPIO_TC0_CLK2_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN15)
+
+#define GPIO_TC1_A0_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN15)
+#define GPIO_TC1_A0_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN0)
+#define GPIO_TC1_A1_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN17)
+#define GPIO_TC1_A1_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN2)
+#define GPIO_TC1_A2_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN19)
+#define GPIO_TC1_A2_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN4)
+#define GPIO_TC1_B0_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN16)
+#define GPIO_TC1_B0_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN1)
+#define GPIO_TC1_B1_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN18)
+#define GPIO_TC1_B1_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN3)
+#define GPIO_TC1_B2_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN20)
+#define GPIO_TC1_B2_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN5)
+#define GPIO_TC1_CLK0_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN21)
+#define GPIO_TC1_CLK0_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN6)
+#define GPIO_TC1_CLK1_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN22)
+#define GPIO_TC1_CLK1_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN7)
+#define GPIO_TC1_CLK2_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN23)
+#define GPIO_TC1_CLK2_2 (GPIO_FUNCD | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN8)
+
+/* Two-wire Master Interface */
+
+#define GPIO_TWIM2_TWCK (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN22)
+#define GPIO_TWIM2_TWD (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN21)
+#define GPIO_TWIM3_TWCK (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN15)
+#define GPIO_TWIM3_TWD (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN14)
+#define GPIO_TWIMS0_TWCK (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN24)
+#define GPIO_TWIMS0_TWD (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN23)
+#define GPIO_TWIMS1_TWCK (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN1)
+#define GPIO_TWIMS1_TWD (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN0)
+
+/* USARTs */
+
+#define GPIO_USART0_CLK_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN10)
+#define GPIO_USART0_CLK_2 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN13)
+#define GPIO_USART0_CLK_3 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN4)
+#define GPIO_USART0_CLK_4 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN0)
+#define GPIO_USART0_CTS_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN9)
+#define GPIO_USART0_CTS_2 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN11)
+#define GPIO_USART0_CTS_3 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN2)
+#define GPIO_USART0_RTS_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN8)
+#define GPIO_USART0_RTS_2 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN12)
+#define GPIO_USART0_RTS_3 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN6)
+#define GPIO_USART0_RTS_4 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN1)
+#define GPIO_USART0_RXD_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN11)
+#define GPIO_USART0_RXD_2 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN14)
+#define GPIO_USART0_RXD_3 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN5)
+#define GPIO_USART0_RXD_4 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN0)
+#define GPIO_USART0_RXD_5 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN2)
+#define GPIO_USART0_TXD_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN12)
+#define GPIO_USART0_TXD_2 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN15)
+#define GPIO_USART0_TXD_3 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN7)
+#define GPIO_USART0_TXD_4 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN1)
+#define GPIO_USART0_TXD_5 (GPIO_FUNCC | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN3)
+
+#define GPIO_USART1_CLK_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN14)
+#define GPIO_USART1_CLK_2 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN25)
+#define GPIO_USART1_CLK_3 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN3)
+#define GPIO_USART1_CTS (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN21)
+#define GPIO_USART1_RTS_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN13)
+#define GPIO_USART1_RTS_2 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN24)
+#define GPIO_USART1_RTS_3 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN2)
+#define GPIO_USART1_RXD_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN15)
+#define GPIO_USART1_RXD_2 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN26)
+#define GPIO_USART1_RXD_3 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN4)
+#define GPIO_USART1_TXD_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN16)
+#define GPIO_USART1_TXD_2 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN27)
+#define GPIO_USART1_TXD_3 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN5)
+
+#define GPIO_USART2_CLK_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN18)
+#define GPIO_USART2_CLK_2 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN8)
+#define GPIO_USART2_CTS_1 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN22)
+#define GPIO_USART2_CTS_2 (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN8)
+#define GPIO_USART2_RTS_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN17)
+#define GPIO_USART2_RTS_2 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN7)
+#define GPIO_USART2_RXD_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN19)
+#define GPIO_USART2_RXD_2 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN25)
+#define GPIO_USART2_RXD_3 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN11)
+#define GPIO_USART2_TXD_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN20)
+#define GPIO_USART2_TXD_2 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN26)
+#define GPIO_USART2_TXD_3 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN12)
+
+#define GPIO_USART3_CLK_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN8)
+#define GPIO_USART3_CLK_2 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN31)
+#define GPIO_USART3_CLK_3 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN14)
+#define GPIO_USART3_CLK_4 (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN29)
+#define GPIO_USART3_CTS_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN7)
+#define GPIO_USART3_CTS_2 (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN28)
+#define GPIO_USART3_RTS_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN6)
+#define GPIO_USART3_RTS_2 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN30)
+#define GPIO_USART3_RTS_3 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN13)
+#define GPIO_USART3_RTS_4 (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN27)
+#define GPIO_USART3_RXD_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN9)
+#define GPIO_USART3_RXD_2 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN28)
+#define GPIO_USART3_RXD_3 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN9)
+#define GPIO_USART3_RXD_4 (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN30)
+#define GPIO_USART3_TXD_1 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOB | GPIO_PIN10)
+#define GPIO_USART3_TXD_2 (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN29)
+#define GPIO_USART3_TXD_3 (GPIO_FUNCB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOC | GPIO_PIN10)
+#define GPIO_USART3_TXD_4 (GPIO_FUNCE | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN31)
+
+/* USB 2.0 Interface */
+
+#define GPIO_USBC_DM (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN25)
+#define GPIO_USBC_DP (GPIO_FUNCA | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN26)
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Inline Functions
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+/************************************************************************************
+ * Public Function Prototypes
+ ************************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_ARM_SRC_SAM34_CHIP_SAM3U_PINMAP_H */
diff --git a/nuttx/configs/sam4l-xplained/README.txt b/nuttx/configs/sam4l-xplained/README.txt
index ca5ecf2f9..ea97942f7 100644
--- a/nuttx/configs/sam4l-xplained/README.txt
+++ b/nuttx/configs/sam4l-xplained/README.txt
@@ -15,6 +15,7 @@ Contents
- NuttX OABI "buildroot" Toolchain
- NXFLAT Toolchain
- LEDs
+ - Virtual COM Port
- SAM4L Xplained Pro-specific Configuration Options
- Configurations
@@ -242,6 +243,17 @@ LEDs
apparently, running normmally. If LED0 is flashing at approximately
2Hz, then a fatal error has been detected and the system has halted.
+Virtual COM Port
+^^^^^^^^^^^^^^^^
+
+ The SAM4L Xplained Pro contains an Embedded Debugger (EDBG) that can be
+ used to program and debug the ATSAM4LC4C using Serial Wire Debug (SWD).
+ The Embedded debugger also include a Virtual Com port interface over
+ USART1. Virtual COM port connections:
+
+ PC26 USART1 RXD
+ PC27 USART1 TXD
+
SAM4L Xplained Pro-specific Configuration Options
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
diff --git a/nuttx/configs/sam4l-xplained/include/board.h b/nuttx/configs/sam4l-xplained/include/board.h
index 3c8cb82e3..cb70aff04 100644
--- a/nuttx/configs/sam4l-xplained/include/board.h
+++ b/nuttx/configs/sam4l-xplained/include/board.h
@@ -156,6 +156,19 @@
#define BUTTON_SW0_BIT (1 << BUTTON_SW0)
+/* Alternate Function Disambiguation ************************************************/
+/* The SAM4L Xplained Pro contains an Embedded Debugger (EDBG) that can be
+ * used to program and debug the ATSAM4LC4C using Serial Wire Debug (SWD).
+ * The Embedded debugger also include a Virtual Com port interface over
+ * USART1. Virtual COM port connections:
+ *
+ * PC26 USART1 RXD
+ * PC27 USART1 TXD
+ */
+
+#define GPIO_USART1_RXD GPIO_USART1_RXD_2
+#define GPIO_USART1_TXD GPIO_USART1_TXD_2
+
/************************************************************************************
* Public Data
************************************************************************************/
diff --git a/nuttx/configs/sam4l-xplained/ostest/defconfig b/nuttx/configs/sam4l-xplained/ostest/defconfig
index e10037477..3cab5109b 100644
--- a/nuttx/configs/sam4l-xplained/ostest/defconfig
+++ b/nuttx/configs/sam4l-xplained/ostest/defconfig
@@ -80,6 +80,7 @@ CONFIG_ARCH_CORTEXM4=y
CONFIG_ARCH_FAMILY="armv7-m"
CONFIG_ARCH_CHIP="sam34"
# CONFIG_ARMV7M_USEBASEPRI is not set
+# CONFIG_ARCH_HAVE_FPU is not set
CONFIG_ARCH_HAVE_MPU=y
# CONFIG_ARMV7M_MPU is not set
@@ -128,9 +129,9 @@ CONFIG_ARCH_CHIP_SAM4L=y
# CONFIG_SAM34_DMA is not set
# CONFIG_SAM34_NAND is not set
# CONFIG_SAM34_HSMCI is not set
-CONFIG_SAM34_UART=y
+# CONFIG_SAM34_UART is not set
# CONFIG_SAM34_USART0 is not set
-# CONFIG_SAM34_USART1 is not set
+CONFIG_SAM34_USART1=y
# CONFIG_SAM34_USART2 is not set
# CONFIG_SAM34_USART3 is not set
# CONFIG_SAM34_SPI is not set
@@ -138,6 +139,7 @@ CONFIG_SAM34_UART=y
#
# AT91SAM3 UART Configuration
#
+CONFIG_USART1_ISUART=y
#
# AT91SAM3 GPIO Interrupt Configuration
@@ -297,20 +299,20 @@ CONFIG_DEV_NULL=y
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_16550_UART is not set
-CONFIG_ARCH_HAVE_UART=y
+CONFIG_ARCH_HAVE_USART1=y
CONFIG_MCU_SERIAL=y
-CONFIG_UART_SERIAL_CONSOLE=y
+CONFIG_USART1_SERIAL_CONSOLE=y
# CONFIG_NO_SERIAL_CONSOLE is not set
#
-# UART Configuration
+# USART1 Configuration
#
-CONFIG_UART_RXBUFSIZE=256
-CONFIG_UART_TXBUFSIZE=256
-CONFIG_UART_BAUD=115200
-CONFIG_UART_BITS=8
-CONFIG_UART_PARITY=0
-CONFIG_UART_2STOP=0
+CONFIG_USART1_RXBUFSIZE=256
+CONFIG_USART1_TXBUFSIZE=256
+CONFIG_USART1_BAUD=115200
+CONFIG_USART1_BITS=8
+CONFIG_USART1_PARITY=0
+CONFIG_USART1_2STOP=0
# CONFIG_USBDEV is not set
# CONFIG_USBHOST is not set
# CONFIG_WIRELESS is not set