summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/ChangeLog3
-rw-r--r--nuttx/arch/arm/Kconfig19
-rw-r--r--nuttx/arch/arm/include/samd/chip.h319
-rw-r--r--nuttx/arch/arm/include/samd/irq.h112
-rwxr-xr-xnuttx/arch/arm/include/samd/samd20_irq.h141
-rw-r--r--nuttx/arch/arm/src/kl/kl_timerisr.c2
-rw-r--r--nuttx/arch/arm/src/nuc1xx/nuc_idle.c2
-rw-r--r--nuttx/arch/arm/src/nuc1xx/nuc_irq.c2
-rw-r--r--nuttx/arch/arm/src/nuc1xx/nuc_timerisr.c2
-rw-r--r--nuttx/arch/arm/src/samd/Kconfig350
-rw-r--r--nuttx/arch/arm/src/samd/Make.defs75
-rw-r--r--nuttx/arch/arm/src/samd/chip.h75
-rw-r--r--nuttx/arch/arm/src/samd/chip/sam_memorymap.h52
-rw-r--r--nuttx/arch/arm/src/samd/chip/samd20_memorymap.h120
-rw-r--r--nuttx/arch/arm/src/samd/sam_clockconfig.h93
-rw-r--r--nuttx/arch/arm/src/samd/sam_config.h189
-rw-r--r--nuttx/arch/arm/src/samd/sam_gpio.h146
-rw-r--r--nuttx/arch/arm/src/samd/sam_idle.c187
-rw-r--r--nuttx/arch/arm/src/samd/sam_irq.c400
-rw-r--r--nuttx/arch/arm/src/samd/sam_irq.h65
-rw-r--r--nuttx/arch/arm/src/samd/sam_lowputc.h112
-rw-r--r--nuttx/arch/arm/src/samd/sam_serial.h68
-rw-r--r--nuttx/arch/arm/src/samd/sam_start.c179
-rw-r--r--nuttx/arch/arm/src/samd/sam_timerisr.c147
-rw-r--r--nuttx/arch/arm/src/samd/sam_userspace.c113
-rw-r--r--nuttx/arch/arm/src/samd/sam_userspace.h76
26 files changed, 3041 insertions, 8 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 70fa40aab..2115b908a 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -6573,3 +6573,6 @@
* MANY files changes based on complaints from the tool CppCheck. Several
latent bugs were fixed (and most likely some new typos were introduced)
(2014-2-10).
+ * arch/arm/include/samd and src/samd: Basic framework to support Atmel
+ SAMD20 Cortex-M0+ chips. Initial check-in is incomplete; this is a
+ work in progress (2014-2-12).
diff --git a/nuttx/arch/arm/Kconfig b/nuttx/arch/arm/Kconfig
index 53a82f8e5..6afcda376 100644
--- a/nuttx/arch/arm/Kconfig
+++ b/nuttx/arch/arm/Kconfig
@@ -121,19 +121,26 @@ config ARCH_CHIP_NUC1XX
NPX LPC43XX architectures (ARM Cortex-M4).
config ARCH_CHIP_SAMA5
- bool "Atmel AT91SAMA5"
+ bool "Atmel SAMA5"
select ARCH_CORTEXA5
select ARCH_HAVE_FPU
select ARCH_HAVE_LOWVECTORS
---help---
- Atmel AT91SAMA5 (ARM Cortex-A5)
+ Atmel SAMA5 (ARM Cortex-A5)
+
+config ARCH_CHIP_SAMD
+ bool "Atmel SAMD"
+ select ARCH_CORTEXM0
+ select ARCH_HAVE_CMNVECTOR
+ ---help---
+ Atmel SAMD (ARM Cortex-M0+)
config ARCH_CHIP_SAM34
- bool "Atmel AT91SAM3/SAM4"
+ bool "Atmel SAM3/SAM4"
select ARCH_HAVE_MPU
select ARCH_HAVE_RAMFUNCS
---help---
- Atmel AT91SAM3 (ARM Cortex-M3) and SAM4 (ARM Cortex-M4) architectures
+ Atmel SAM3 (ARM Cortex-M3) and SAM4 (ARM Cortex-M4) architectures
config ARCH_CHIP_STM32
bool "STMicro STM32"
@@ -222,6 +229,7 @@ config ARCH_CHIP
default "lpc43xx" if ARCH_CHIP_LPC43XX
default "nuc1xx" if ARCH_CHIP_NUC1XX
default "sama5" if ARCH_CHIP_SAMA5
+ default "samd" if ARCH_CHIP_SAMD
default "sam34" if ARCH_CHIP_SAM34
default "stm32" if ARCH_CHIP_STM32
default "str71x" if ARCH_CHIP_STR71X
@@ -380,6 +388,9 @@ endif
if ARCH_CHIP_SAMA5
source arch/arm/src/sama5/Kconfig
endif
+if ARCH_CHIP_SAMD
+source arch/arm/src/samd/Kconfig
+endif
if ARCH_CHIP_SAM34
source arch/arm/src/sam34/Kconfig
endif
diff --git a/nuttx/arch/arm/include/samd/chip.h b/nuttx/arch/arm/include/samd/chip.h
new file mode 100644
index 000000000..8e6b4682f
--- /dev/null
+++ b/nuttx/arch/arm/include/samd/chip.h
@@ -0,0 +1,319 @@
+/************************************************************************************
+ * arch/arm/include/samd/chip.h
+ *
+ * Copyright (C) 2014 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_INCLUDE_SAMD_CHIP_H
+#define __ARCH_ARM_INCLUDE_SAMD_CHIP_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Get customizations for each supported chip */
+
+/* SAMD20 Family ********************************************************************/
+/* FEATURE SAM D20J SAM D20G SAM D20E
+ * ------------------- ------------------ ------------------ --------
+ * No. of pins 64 48 32
+ * Flash 256/128/64/32/16KB 256/128/64/32/16KB 256/128/64/32/16KB
+ * SRAM 32/16/8/4/2KB 32/16/8/4/2KB 32/16/8/4/2KB
+ * Max. Freq. 48MHz 48MHz 48MHz
+ * Event channels 8 8 8
+ * Timer/counters 8 6 6
+ * TC output channels 2 2 2
+ * SERCOMM 6 6 4
+ * ADC channels 20 14 10
+ * Comparators 2 2 2
+ * DAC channels 1 1 1
+ * RTC Yes Yes Yes
+ * RTC alarms 1 1 1
+ * RTC compare 1 32-bit/2 16-bit 1 32-bit/2 16-bit 1 32-bit/2 16-bit
+ * External interrupts 16 16 16
+ * PTC X an Y 16x16 12x10 10x6
+ * Packages QFN/TQFP QFN/TQFP QFN/TQFP
+ * Oscillators XOSC32, XOSC, OSC32K, OSCULP32K, OSC8M, and DFLL48M
+ * SW Debug interface Yes Yes Yes
+ * Watchdog timer Yes Yes Yes
+ */
+
+#if defined(CONFIG_ARCH_CHIP_SAMD20E14)
+
+# define SAMD20 1 /* SAMD20 family */
+# define SAMD20E 1 /* SAMD20E */
+# undef SAMD20G
+# undef SAMD20J
+
+/* Internal memory */
+
+# define SAMD_FLASH_SIZE (16*1024) /* 16KB */
+# define SAMD_SRAM0_SIZE (2*1024) /* 2KB */
+
+#elif defined(CONFIG_ARCH_CHIP_SAMD20E15)
+
+# define SAMD20 1 /* SAMD20 family */
+# define SAMD20E 1 /* SAMD20E */
+# undef SAMD20G
+# undef SAMD20J
+
+/* Internal memory */
+
+# define SAMD_FLASH_SIZE (32*1024) /* 32KB */
+# define SAMD_SRAM0_SIZE (4*1024) /* 4KB */
+
+#elif defined(CONFIG_ARCH_CHIP_SAMD20E16)
+
+# define SAMD20 1 /* SAMD20 family */
+# define SAMD20E 1 /* SAMD20E */
+# undef SAMD20G
+# undef SAMD20J
+
+/* Internal memory */
+
+# define SAMD_FLASH_SIZE (64*1024) /* 64KB */
+# define SAMD_SRAM0_SIZE (8*1024) /* 8KB */
+
+#elif defined(CONFIG_ARCH_CHIP_SAMD20E17)
+
+# define SAMD20 1 /* SAMD20 family */
+# define SAMD20E 1 /* SAMD20E */
+# undef SAMD20G
+# undef SAMD20J
+
+/* Internal memory */
+
+# define SAMD_FLASH_SIZE (128*1024) /* 128KB */
+# define SAMD_SRAM0_SIZE (16*1024) /* 16KB */
+
+#elif defined(CONFIG_ARCH_CHIP_SAMD20E18)
+
+# define SAMD20 1 /* SAMD20 family */
+# define SAMD20E 1 /* SAMD20E */
+# undef SAMD20G
+# undef SAMD20J
+
+/* Internal memory */
+
+# define SAMD_FLASH_SIZE (256*1024) /* 256KB */
+# define SAMD_SRAM0_SIZE (32*1024) /* 32KB */
+
+#elif defined(CONFIG_ARCH_CHIP_SAMD20G14)
+
+# define SAMD20 1 /* SAMD20 family */
+# undef SAMD20E
+# define SAMD20G 1 /* SAMD20G */
+# undef SAMD20J
+
+/* Internal memory */
+
+# define SAMD_FLASH_SIZE (16*1024) /* 16KB */
+# define SAMD_SRAM0_SIZE (2*1024) /* 2KB */
+
+#elif defined(CONFIG_ARCH_CHIP_SAMD20G15)
+
+# define SAMD20 1 /* SAMD20 family */
+# undef SAMD20E
+# define SAMD20G 1 /* SAMD20G */
+# undef SAMD20J
+
+/* Internal memory */
+
+# define SAMD_FLASH_SIZE (32*1024) /* 32KB */
+# define SAMD_SRAM0_SIZE (4*1024) /* 4KB */
+
+#elif defined(CONFIG_ARCH_CHIP_SAMD20G16)
+
+# define SAMD20 1 /* SAMD20 family */
+# undef SAMD20E
+# define SAMD20G 1 /* SAMD20G */
+# undef SAMD20J
+
+/* Internal memory */
+
+# define SAMD_FLASH_SIZE (64*1024) /* 64KB */
+# define SAMD_SRAM0_SIZE (8*1024) /* 8KB */
+
+#elif defined(CONFIG_ARCH_CHIP_SAMD20G17)
+
+# define SAMD20 1 /* SAMD20 family */
+# undef SAMD20E
+# define SAMD20G 1 /* SAMD20G */
+# undef SAMD20J
+
+/* Internal memory */
+
+# define SAMD_FLASH_SIZE (128*1024) /* 128KB */
+# define SAMD_SRAM0_SIZE (16*1024) /* 16KB */
+
+#elif defined(CONFIG_ARCH_CHIP_SAMD20G18)
+
+# define SAMD20 1 /* SAMD20 family */
+# undef SAMD20E
+# define SAMD20G 1 /* SAMD20G */
+# undef SAMD20J
+
+/* Internal memory */
+
+# define SAMD_FLASH_SIZE (256*1024) /* 256KB */
+# define SAMD_SRAM0_SIZE (32*1024) /* 32KB */
+
+#elif defined(CONFIG_ARCH_CHIP_SAMD20J14)
+
+# define SAMD20 1 /* SAMD20 family */
+# undef SAMD20E
+# undef SAMD20G
+# define SAMD20J 1 /* SAMD20J */
+
+/* Internal memory */
+
+# define SAMD_FLASH_SIZE (16*1024) /* 16KB */
+# define SAMD_SRAM0_SIZE (2*1024) /* 2KB */
+
+#elif defined(CONFIG_ARCH_CHIP_SAMD20J15)
+
+# define SAMD20 1 /* SAMD20 family */
+# undef SAMD20E
+# undef SAMD20G
+# define SAMD20J 1 /* SAMD20J */
+
+/* Internal memory */
+
+# define SAMD_FLASH_SIZE (32*1024) /* 32KB */
+# define SAMD_SRAM0_SIZE (4*1024) /* 4KB */
+
+#elif defined(CONFIG_ARCH_CHIP_SAMD20J16)
+
+# define SAMD20 1 /* SAMD20 family */
+# undef SAMD20E
+# undef SAMD20G
+# define SAMD20J 1 /* SAMD20J */
+
+/* Internal memory */
+
+# define SAMD_FLASH_SIZE (64*1024) /* 64KB */
+# define SAMD_SRAM0_SIZE (8*1024) /* 8KB */
+
+#elif defined(CONFIG_ARCH_CHIP_SAMD20J17)
+
+# define SAMD20 1 /* SAMD20 family */
+# undef SAMD20E
+# undef SAMD20G
+# define SAMD20J 1 /* SAMD20J */
+
+/* Internal memory */
+
+# define SAMD_FLASH_SIZE (128*1024) /* 128KB */
+# define SAMD_SRAM0_SIZE (16*1024) /* 16KB */
+
+#elif defined(CONFIG_ARCH_CHIP_SAMD20J18)
+
+# define SAMD20 1 /* SAMD20 family */
+# undef SAMD20E
+# undef SAMD20G
+# define SAMD20J 1 /* SAMD20J */
+
+/* Internal memory */
+
+# define SAMD_FLASH_SIZE (256*1024) /* 256KB */
+# define SAMD_SRAM0_SIZE (32*1024) /* 32KB */
+
+#endif
+
+/* SAMD20 Peripherals */
+
+#if defined(SAMD20E)
+# define SAMD_NEVENTS 8 /* 8 event channels */
+# define SAMD_NTC 6 /* 6 Timer/counters */
+# define SAMD_NTCOUT 2 /* 2 TC output channels */
+# define SAMD_NSERCOMM 4 /* 4 SERCOMM */
+# define SAMD_NADC 10 /* 10 ADC channels */
+# define SAMD_NCMP 2 /* 2 Comparators */
+# define SAMD_NDAC 1 /* 1 DAC channel */
+# define SAMD_RTC 1 /* Have RTC */
+# define SAMD_NALARMS 1 /* 1 RTC alarm */
+# define SAMD_NRTCMP 1 /* RTC compare: 1 32-bit/2 16-bit */
+# define SAMD_NEXTINT 16 /* 16 External interrupts */
+# define SAMD_NPTCX 10 /* PTC X */
+# define SAMD_NPTCY 6 /* PTC Y */
+# define SAMD_WDT /* Have watchdog timer */
+#elseif defined(SAMD20G)
+# define SAMD_NEVENTS 8 /* 8 event channels */
+# define SAMD_NTC 6 /* 6 Timer/counters */
+# define SAMD_NTCOUT 2 /* 2 TC output channels */
+# define SAMD_NSERCOMM 6 /* 6 SERCOMM */
+# define SAMD_NADC 15 /* 14 ADC channels */
+# define SAMD_NCMP 2 /* 2 Comparators */
+# define SAMD_NDAC 1 /* 1 DAC channel */
+# define SAMD_RTC 1 /* Have RTC */
+# define SAMD_NALARMS 1 /* 1 RTC alarm */
+# define SAMD_NRTCMP 1 /* RTC compare: 1 32-bit/2 16-bit */
+# define SAMD_NEXTINT 16 /* 16 External interrupts */
+# define SAMD_NPTCX 12 /* PTC X */
+# define SAMD_NPTCY 10 /* PTC Y */
+# define SAMD_WDT /* Have watchdog timer */
+#elseif defined(SAMD20J)
+# define SAMD_NEVENTS 8 /* 8 event channels */
+# define SAMD_NTC 8 /* 8 Timer/counters */
+# define SAMD_NTCOUT 2 /* 2 TC output channels */
+# define SAMD_NSERCOMM 6 /* 6 SERCOMM */
+# define SAMD_NADC 20 /* 20 ADC channels */
+# define SAMD_NCMP 2 /* 2 Comparators */
+# define SAMD_NDAC 1 /* 1 DAC channel */
+# define SAMD_RTC 1 /* Have RTC */
+# define SAMD_NALARMS 1 /* 1 RTC alarm */
+# define SAMD_NRTCMP 1 /* RTC compare: 1 32-bit/2 16-bit */
+# define SAMD_NEXTINT 16 /* 16 External interrupts */
+# define SAMD_NPTCX 16 /* PTC X */
+# define SAMD_NPTCY 16 /* PTC Y */
+# define SAMD_WDT /* Have watchdog timer */
+#endif
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_INCLUDE_SAMD_CHIP_H */
diff --git a/nuttx/arch/arm/include/samd/irq.h b/nuttx/arch/arm/include/samd/irq.h
new file mode 100644
index 000000000..a8855fda2
--- /dev/null
+++ b/nuttx/arch/arm/include/samd/irq.h
@@ -0,0 +1,112 @@
+/****************************************************************************************
+ * arch/arm/include/samd/irq.h
+ *
+ * Copyright (C) 2014 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.
+ *
+ ****************************************************************************************/
+
+/* This file should never be included directed but, rather, only indirectly through
+ * nuttx/irq.h
+ */
+
+#ifndef __ARCH_ARM_INCLUDE_SAMD_IRQ_H
+#define __ARCH_ARM_INCLUDE_SAMD_IRQ_H
+
+/****************************************************************************************
+ * Included Files
+ ****************************************************************************************/
+
+#include <nuttx/config.h>
+#include <arch/samd/chip.h>
+
+/****************************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************************/
+
+/* IRQ numbers. The IRQ number corresponds vector number and hence map directly to
+ * bits in the NVIC. This does, however, waste several words of memory in the IRQ
+ * to handle mapping tables.
+ */
+
+/* Processor Exceptions (vectors 0-15) */
+
+#define SAM_IRQ_RESERVED (0) /* Reserved vector (only used with CONFIG_DEBUG) */
+ /* Vector 0: Reset stack pointer value */
+ /* Vector 1: Reset (not handler as an IRQ) */
+#define SAM_IRQ_NMI (2) /* Vector 2: Non-Maskable Interrupt (NMI) */
+#define SAM_IRQ_HARDFAULT (3) /* Vector 3: Hard fault */
+ /* Vector 4-10: Reserved */
+#define SAM_IRQ_SVCALL (11) /* Vector 11: SVC call */
+ /* Vector 12-13: Reserved */
+#define SAM_IRQ_PENDSV (14) /* Vector 14: Pendable system service request */
+#define SAM_IRQ_SYSTICK (15) /* Vector 15: System tick */
+
+/* External interrupts (vectors >= 16). These definitions are chip-specific */
+
+#define SAM_IRQ_INTERRUPT (16) /* Vector number of the first external interrupt */
+
+/* Chip-Specific External interrupts */
+
+#if defined(SAMD20)
+# include <arch/samd/samd20_irq.h>
+#else
+# error "Unrecognized/unsupported SAMD chip"
+#endif
+
+/****************************************************************************************
+ * Public Types
+ ****************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/****************************************************************************************
+ * Public Data
+ ****************************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************************/
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+#endif
+
+#endif /* __ARCH_ARM_INCLUDE_SAMD_IRQ_H */
diff --git a/nuttx/arch/arm/include/samd/samd20_irq.h b/nuttx/arch/arm/include/samd/samd20_irq.h
new file mode 100755
index 000000000..199c644f7
--- /dev/null
+++ b/nuttx/arch/arm/include/samd/samd20_irq.h
@@ -0,0 +1,141 @@
+/****************************************************************************************
+ * arch/arm/include/samd/samd20_irq.h
+ *
+ * Copyright (C) 2014 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.
+ *
+ ****************************************************************************************/
+
+/* This file should never be included directed but, rather, only indirectly through
+ * nuttx/irq.h
+ */
+
+#ifndef __ARCH_ARM_INCLUDE_SAMD_SAMD20_IRQ_H
+#define __ARCH_ARM_INCLUDE_SAMD_SAMD20_IRQ_H
+
+/****************************************************************************************
+ * Included Files
+ ****************************************************************************************/
+
+/****************************************************************************************
+ * Definitions
+ ****************************************************************************************/
+
+/* External interrupts */
+
+#define SAM_IRQ_PM (SAM_IRQ_INTERRUPT+0) /* Power Manager */
+#define SAM_IRQ_SYSCTRL (SAM_IRQ_INTERRUPT+1) /* System Controller */
+#define SAM_IRQ_WDT (SAM_IRQ_INTERRUPT+2) /* Watchdog Timer */
+#define SAM_IRQ_RTC (SAM_IRQ_INTERRUPT+3) /* Real Time Counter */
+#define SAM_IRQ_EIC (SAM_IRQ_INTERRUPT+4) /* External Interrupt Controller */
+#define SAM_IRQ_NVMCTRL (SAM_IRQ_INTERRUPT+5) /* Non-Volatile Memory Controller */
+#define SAM_IRQ_EVSYS (SAM_IRQ_INTERRUPT+6) /* Event System */
+#define SAM_IRQ_SERCOM0 (SAM_IRQ_INTERRUPT+7) /* Serial Communication Interface 0 */
+#define SAM_IRQ_SERCOM1 (SAM_IRQ_INTERRUPT+8) /* Serial Communication Interface 1 */
+#define SAM_IRQ_SERCOM2 (SAM_IRQ_INTERRUPT+9) /* Serial Communication Interface 2 */
+#define SAM_IRQ_SERCOM3 (SAM_IRQ_INTERRUPT+10) /* Serial Communication Interface 3 */
+#define SAM_IRQ_SERCOM4 (SAM_IRQ_INTERRUPT+11) /* Serial Communication Interface 4 */
+#define SAM_IRQ_SERCOM5 (SAM_IRQ_INTERRUPT+12) /* Serial Communication Interface 5 */
+#define SAM_IRQ_TC0 (SAM_IRQ_INTERRUPT+13) /* Timer/Counter 0 */
+#define SAM_IRQ_TC1 (SAM_IRQ_INTERRUPT+14) /* Timer/Counter 1 */
+#define SAM_IRQ_TC2 (SAM_IRQ_INTERRUPT+15) /* Timer/Counter 2 */
+#define SAM_IRQ_TC3 (SAM_IRQ_INTERRUPT+16) /* Timer/Counter 3 */
+#define SAM_IRQ_TC4 (SAM_IRQ_INTERRUPT+17) /* Timer/Counter 4 */
+#define SAM_IRQ_TC5 (SAM_IRQ_INTERRUPT+18) /* Timer/Counter 5 */
+#define SAM_IRQ_TC6 (SAM_IRQ_INTERRUPT+19) /* Timer/Counter 6 */
+#define SAM_IRQ_TC7 (SAM_IRQ_INTERRUPT+20) /* Timer/Counter 7 */
+#define SAM_IRQ_ADC (SAM_IRQ_INTERRUPT+21) /* Analog-to-Digital Converter */
+#define SAM_IRQ_AC (SAM_IRQ_INTERRUPT+22) /* Analog Comparator */
+#define SAM_IRQ_DAC (SAM_IRQ_INTERRUPT+23) /* Digital-to-Analog Converter */
+#define SAM_IRQ_PTC (SAM_IRQ_INTERRUPT+24) /* Peripheral Touch Controller*/
+
+#define SAM_IRQ_NINTS (25) /* Total number of interrupts */
+#define SAM_IRQ_NIRQS (SAM_IRQ_INTERRUPT+25) /* The number of real interrupts */
+
+/* GPIO interrupts. Up to 16 pins may be configured to support interrupts */
+
+#ifdef CONFIG_GPIO_IRQ
+# define SAM_IRQ_EXTINT0 (SAM_IRQ_NIRQS+0) /* External interrupt 0 */
+# define SAM_IRQ_EXTINT1 (SAM_IRQ_NIRQS+1) /* External interrupt 1 */
+# define SAM_IRQ_EXTINT2 (SAM_IRQ_NIRQS+2) /* External interrupt 2 */
+# define SAM_IRQ_EXTINT3 (SAM_IRQ_NIRQS+3) /* External interrupt 3 */
+# define SAM_IRQ_EXTINT4 (SAM_IRQ_NIRQS+4) /* External interrupt 4 */
+# define SAM_IRQ_EXTINT5 (SAM_IRQ_NIRQS+5) /* External interrupt 5 */
+# define SAM_IRQ_EXTINT6 (SAM_IRQ_NIRQS+6) /* External interrupt 6 */
+# define SAM_IRQ_EXTINT7 (SAM_IRQ_NIRQS+7) /* External interrupt 7 */
+# define SAM_IRQ_EXTINT8 (SAM_IRQ_NIRQS+8) /* External interrupt 8 */
+# define SAM_IRQ_EXTINT9 (SAM_IRQ_NIRQS+9) /* External interrupt 9 */
+# define SAM_IRQ_EXTINT10 (SAM_IRQ_NIRQS+10) /* External interrupt 10 */
+# define SAM_IRQ_EXTINT11 (SAM_IRQ_NIRQS+11) /* External interrupt 11 */
+# define SAM_IRQ_EXTINT12 (SAM_IRQ_NIRQS+12) /* External interrupt 12 */
+# define SAM_IRQ_EXTINT13 (SAM_IRQ_NIRQS+13) /* External interrupt 13 */
+# define SAM_IRQ_EXTINT14 (SAM_IRQ_NIRQS+14) /* External interrupt 14 */
+# define SAM_IRQ_EXTINT15 (SAM_IRQ_NIRQS+15) /* External interrupt 15 */
+# define SAM_IRQ_NEXTINTS 16
+#else
+# define SAM_IRQ_NEXTINTS 0
+#endif
+
+/* Total number of IRQ numbers */
+
+#define NR_VECTORS SAM_IRQ_NIRQS
+#define NR_IRQS (SAM_IRQ_INTERRUPT + SAM_IRQ_NINTS + SAM_IRQ_NEXTINTS)
+
+/****************************************************************************************
+ * Public Types
+ ****************************************************************************************/
+
+/****************************************************************************************
+ * Inline functions
+ ****************************************************************************************/
+
+/****************************************************************************************
+ * Public Variables
+ ****************************************************************************************/
+
+/****************************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************************/
+
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+#endif
+
+#endif /* __ARCH_ARM_INCLUDE_SAMD_SAMD20_IRQ_H */
diff --git a/nuttx/arch/arm/src/kl/kl_timerisr.c b/nuttx/arch/arm/src/kl/kl_timerisr.c
index 409ccd063..94c982cbf 100644
--- a/nuttx/arch/arm/src/kl/kl_timerisr.c
+++ b/nuttx/arch/arm/src/kl/kl_timerisr.c
@@ -79,7 +79,7 @@
* = 119,999
* = 0x1d4bf
*
- * Which fits within the maximum 14-bit reload value.
+ * Which fits within the maximum 24-bit reload value.
*/
#define SYSTICK_RELOAD ((SYSTICK_CLOCK / CLK_TCK) - 1)
diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_idle.c b/nuttx/arch/arm/src/nuc1xx/nuc_idle.c
index 74ff353f1..7daa5ca95 100644
--- a/nuttx/arch/arm/src/nuc1xx/nuc_idle.c
+++ b/nuttx/arch/arm/src/nuc1xx/nuc_idle.c
@@ -1,5 +1,5 @@
/****************************************************************************
- * arch/arm/src/stm32/nuc_idle.c
+ * arch/arm/src/nuc1xx/nuc_idle.c
*
* Copyright (C) 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_irq.c b/nuttx/arch/arm/src/nuc1xx/nuc_irq.c
index e45121b13..364bb7f0f 100644
--- a/nuttx/arch/arm/src/nuc1xx/nuc_irq.c
+++ b/nuttx/arch/arm/src/nuc1xx/nuc_irq.c
@@ -1,5 +1,5 @@
/****************************************************************************
- * arch/arm/src/stm32/nuc_irq.c
+ * arch/arm/src/nuc1xx/nuc_irq.c
*
* Copyright (C) 2009-2014 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_timerisr.c b/nuttx/arch/arm/src/nuc1xx/nuc_timerisr.c
index e1f322320..6f0ce6008 100644
--- a/nuttx/arch/arm/src/nuc1xx/nuc_timerisr.c
+++ b/nuttx/arch/arm/src/nuc1xx/nuc_timerisr.c
@@ -86,7 +86,7 @@
* = 119,999
* = 0x1d4bf
*
- * Which fits within the maximum 14-bit reload value.
+ * Which fits within the maximum 24-bit reload value.
*/
#define SYSTICK_RELOAD ((SYSTICK_CLOCK / CLK_TCK) - 1)
diff --git a/nuttx/arch/arm/src/samd/Kconfig b/nuttx/arch/arm/src/samd/Kconfig
new file mode 100644
index 000000000..1474c0665
--- /dev/null
+++ b/nuttx/arch/arm/src/samd/Kconfig
@@ -0,0 +1,350 @@
+#
+# For a description of the syntax of this configuration file,
+# see misc/tools/kconfig-language.txt.
+#
+
+comment "Atmel SAMD Configuration Options"
+
+choice
+ prompt "Atmel SAMD Chip Selection"
+ default ARCH_CHIP_SAMD20J18
+ depends on ARCH_CHIP_SAMD
+
+config ARCH_CHIP_SAMD20E14
+ bool "SAMD20E14"
+ select ARCH_FAMILY_SAMD20
+ select ARCH_FAMILY_SAMD20E
+ ---help---
+ Flash 16KB SRAM 2KB
+
+config ARCH_CHIP_SAMD20E15
+ bool "SAMD20E14"
+ select ARCH_FAMILY_SAMD20
+ select ARCH_FAMILY_SAMD20E
+ ---help---
+ Flash 32KB SRAM 4KB
+
+config ARCH_CHIP_SAMD20E16
+ bool "SAMD20E14"
+ select ARCH_FAMILY_SAMD20
+ select ARCH_FAMILY_SAMD20E
+ ---help---
+ Flash 64KB SRAM 8KB
+
+config ARCH_CHIP_SAMD20E17
+ bool "SAMD20E14"
+ select ARCH_FAMILY_SAMD20
+ select ARCH_FAMILY_SAMD20E
+ ---help---
+ Flash 128KB SRAM 16KB
+
+config ARCH_CHIP_SAMD20E18
+ bool "SAMD20E14"
+ select ARCH_FAMILY_SAMD20
+ select ARCH_FAMILY_SAMD20E
+ ---help---
+ Flash 256KB SRAM 32KB
+
+config ARCH_CHIP_SAMD20G14
+ bool "SAMD20G14"
+ select ARCH_FAMILY_SAMD20
+ select ARCH_FAMILY_SAMD20G
+ ---help---
+ Flash 16KB SRAM 2KB
+
+config ARCH_CHIP_SAMD20G15
+ bool "SAMD20G14"
+ select ARCH_FAMILY_SAMD20
+ select ARCH_FAMILY_SAMD20G
+ ---help---
+ Flash 32KB SRAM 4KB
+
+config ARCH_CHIP_SAMD20G16
+ bool "SAMD20G14"
+ select ARCH_FAMILY_SAMD20
+ select ARCH_FAMILY_SAMD20G
+ ---help---
+ Flash 64KB SRAM 8KB
+
+config ARCH_CHIP_SAMD20G17
+ bool "SAMD20G14"
+ select ARCH_FAMILY_SAMD20
+ select ARCH_FAMILY_SAMD20G
+ ---help---
+ Flash 128KB SRAM 16KB
+
+config ARCH_CHIP_SAMD20G18
+ bool "SAMD20G14"
+ select ARCH_FAMILY_SAMD20
+ select ARCH_FAMILY_SAMD20G
+ ---help---
+ Flash 256KB SRAM 32KB
+
+config ARCH_CHIP_SAMD20J14
+ bool "SAMD20J14"
+ select ARCH_FAMILY_SAMD20
+ select ARCH_FAMILY_SAMD20J
+ ---help---
+ Flash 16KB SRAM 2KB
+
+config ARCH_CHIP_SAMD20J15
+ bool "SAMD20J14"
+ select ARCH_FAMILY_SAMD20
+ select ARCH_FAMILY_SAMD20J
+ ---help---
+ Flash 32KB SRAM 4KB
+
+config ARCH_CHIP_SAMD20J16
+ bool "SAMD20J14"
+ select ARCH_FAMILY_SAMD20
+ select ARCH_FAMILY_SAMD20J
+ ---help---
+ Flash 64KB SRAM 8KB
+
+config ARCH_CHIP_SAMD20J17
+ bool "SAMD20J14"
+ select ARCH_FAMILY_SAMD20
+ select ARCH_FAMILY_SAMD20J
+ ---help---
+ Flash 128KB SRAM 16KB
+
+config ARCH_CHIP_SAMD20J18
+ bool "SAMD20J14"
+ select ARCH_FAMILY_SAMD20
+ select ARCH_FAMILY_SAMD20J
+ ---help---
+ Flash 256KB SRAM 32KB
+
+endchoice
+
+config ARCH_FAMILY_SAMD20
+ bool
+ default n
+
+config ARCH_FAMILY_SAMD20E
+ bool
+ default n
+
+config ARCH_FAMILY_SAMD20G
+ bool
+ default n
+ select SAMD_HAVE_SERCOM4
+ select SAMD_HAVE_SERCOM5
+
+config ARCH_FAMILY_SAMD20J
+ bool
+ default n
+ select SAMD_HAVE_SERCOM4
+ select SAMD_HAVE_SERCOM5
+ select SAMD_HAVE_TC6
+ select SAMD_HAVE_TC7
+
+menu "SAMD Peripheral Support"
+
+config SAMD_WDT
+ bool "Watchdog Timer"
+ default n
+
+config SAMD_RTC
+ bool "Real Time Counter"
+ default n
+
+config SAMD_NVMCTRL
+ bool "Non-Volatile Memory Controller"
+ default n
+
+config SAMD_EVSYS
+ bool "Event System"
+ default n
+
+config SAMD_SERCOM0
+ bool "Serial Communication Interface 0"
+ default n
+
+config SAMD_SERCOM1
+ bool "Serial Communication Interface 1"
+ default n
+
+config SAMD_SERCOM2
+ bool "Serial Communication Interface 2"
+ default n
+
+config SAMD_SERCOM3
+ bool "Serial Communication Interface 3"
+ default n
+
+config SAMD_SERCOM4
+ bool "Serial Communication Interface 4"
+ default n
+ depends on SAMD_HAVE_SERCOM4
+
+config SAMD_SERCOM5
+ bool "Serial Communication Interface 5"
+ default n
+ depends on SAMD_HAVE_SERCOM5
+
+config SAMD_TC0
+ bool "Timer/Counter 0"
+ default n
+
+config SAMD_TC1
+ bool "Timer/Counter 1"
+ default n
+
+config SAMD_TC2
+ bool "Timer/Counter 2"
+ default n
+
+config SAMD_TC3
+ bool "Timer/Counter 3"
+ default n
+
+config SAMD_TC4
+ bool "Timer/Counter 4"
+ default n
+
+config SAMD_TC5
+ bool "Timer/Counter 5"
+ default n
+
+config SAMD_TC6
+ bool "Timer/Counter 6"
+ default n
+ depends on SAMD_HAVE_TC6
+
+config SAMD_TC7
+ bool "Timer/Counter 7"
+ default n
+ depends on SAMD_HAVE_TC7
+
+config SAMD_ADC
+ bool "Analog-to-Digital Converter"
+ default n
+
+config SAMD_AC
+ bool "Analog Comparator"
+ default n
+
+config SAMD_DAC
+ bool "Digital-to-Analog Converter"
+ default n
+
+config SAMD_PTC
+ bool "Peripheral Touch Controller"
+ default n
+
+endmenu
+
+choice
+ prompt "SERCOM0 mode"
+ default SAM_SERCOM0_UART
+ depends on SAMD_SERCOM0
+
+config SAM_SERCOM0_I2C
+bool "I2C"
+select I2C
+
+config SAM_SERCOM0_SPI
+bool "SPI"
+select SPI
+
+config SAM_SERCOM0_UART
+bool "UART"
+select ARCH_HAVE_UART0
+
+endchoice
+
+choice
+ prompt "SERCOM1 mode"
+ default SAM_SERCOM1_UART
+ depends on SAMD_SERCOM1
+
+config SAM_SERCOM1_I2C
+bool "I2C"
+select I2C
+
+config SAM_SERCOM1_SPI
+bool "SPI"
+select SPI
+
+config SAM_SERCOM1_UART
+bool "UART"
+select ARCH_HAVE_UART1
+
+endchoice
+
+choice
+ prompt "SERCOM2 mode"
+ default SAM_SERCOM2_UART
+ depends on SAMD_SERCOM2
+
+config SAM_SERCOM2_I2C
+bool "I2C"
+select I2C
+
+config SAM_SERCOM2_SPI
+bool "SPI"
+select SPI
+
+config SAM_SERCOM2_UART
+bool "UART"
+select ARCH_HAVE_UART2
+
+endchoice
+
+choice
+ prompt "SERCOM3 mode"
+ default SAM_SERCOM3_UART
+ depends on SAMD_SERCOM3
+
+config SAM_SERCOM3_I2C
+bool "I2C"
+select I2C
+
+config SAM_SERCOM3_SPI
+bool "SPI"
+select SPI
+
+config SAM_SERCOM3_UART
+bool "UART"
+select ARCH_HAVE_UART3
+
+endchoice
+
+choice
+ prompt "SERCOM4 mode"
+ default SAM_SERCOM4_UART
+ depends on SAMD_SERCOM4
+
+config SAM_SERCOM4_I2C
+bool "I2C"
+select I2C
+
+config SAM_SERCOM4_SPI
+bool "SPI"
+select SPI
+
+config SAM_SERCOM4_UART
+bool "UART"
+select ARCH_HAVE_UART4
+
+endchoice
+
+choice
+ prompt "SERCOM5 mode"
+ default SAM_SERCOM5_UART
+ depends on SAMD_SERCOM5
+
+config SAM_SERCOM5_I2C
+bool "I2C"
+select I2C
+
+config SAM_SERCOM5_SPI
+bool "SPI"
+select SPI
+
+config SAM_SERCOM5_UART
+bool "UART"
+select ARCH_HAVE_UART5
+
+endchoice
diff --git a/nuttx/arch/arm/src/samd/Make.defs b/nuttx/arch/arm/src/samd/Make.defs
new file mode 100644
index 000000000..05430923b
--- /dev/null
+++ b/nuttx/arch/arm/src/samd/Make.defs
@@ -0,0 +1,75 @@
+############################################################################
+# arch/arm/src/samd/Make.defs
+#
+# Copyright (C) 2014 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.
+#
+############################################################################
+
+HEAD_ASRC =
+
+CMN_ASRCS = up_exception.S up_saveusercontext.S up_fullcontextrestore.S
+CMN_ASRCS += up_switchcontext.S vfork.S
+
+CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copyfullstate.c
+CMN_CSRCS += up_createstack.c up_mdelay.c up_udelay.c up_exit.c
+CMN_CSRCS += up_initialize.c up_initialstate.c up_interruptcontext.c
+CMN_CSRCS += up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c
+CMN_CSRCS += up_releasepending.c up_releasestack.c up_reprioritizertr.c
+CMN_CSRCS += up_schedulesigaction.c up_sigdeliver.c up_systemreset.c
+CMN_CSRCS += up_unblocktask.c up_usestack.c up_doirq.c up_hardfault.c
+CMN_CSRCS += up_svcall.c up_vectors.c up_vfork.c
+
+ifeq ($(CONFIG_NUTTX_KERNEL),y)
+CMN_CSRCS += up_task_start.c up_pthread_start.c up_stackframe.c
+ifneq ($(CONFIG_DISABLE_SIGNALS),y)
+CMN_CSRCS += up_signal_dispatch.c
+CMN_UASRCS += up_signal_handler.S
+endif
+endif
+
+ifeq ($(CONFIG_DEBUG_STACK),y)
+CMN_CSRCS += up_checkstack.c
+endif
+
+ifeq ($(CONFIG_ELF),y)
+CMN_CSRCS += up_elf.c
+endif
+
+ifeq ($(CONFIG_DEBUG),y)
+CMN_CSRCS += up_dumpnvic.c
+endif
+
+CHIP_ASRCS =
+CHIP_CSRCS = sam_idle.c sam_irq.c sam_start.c sam_timerisr.c
+
+ifeq ($(CONFIG_NUTTX_KERNEL),y)
+CHIP_CSRCS += sam_userspace.c
+endif
diff --git a/nuttx/arch/arm/src/samd/chip.h b/nuttx/arch/arm/src/samd/chip.h
new file mode 100644
index 000000000..1b7d17a5f
--- /dev/null
+++ b/nuttx/arch/arm/src/samd/chip.h
@@ -0,0 +1,75 @@
+/************************************************************************************
+ * arch/arm/src/samd/chip.h
+ *
+ * Copyright (C) 2014 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_SAMD_CHIP_H
+#define __ARCH_ARM_SRC_SAMD_CHIP_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/* Include the chip capabilities file */
+
+#include <arch/samd/chip.h>
+
+/* Define the number of interrupt vectors that need to be supported for this chip */
+
+#define ARMV6M_PERIPHERAL_INTERRUPTS 25
+
+/* Include the memory map file. Other chip hardware files should then include
+ * this file for the proper setup.
+ */
+
+#include "chip/sam_memorymap.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_SAMD_CHIP_H */
diff --git a/nuttx/arch/arm/src/samd/chip/sam_memorymap.h b/nuttx/arch/arm/src/samd/chip/sam_memorymap.h
new file mode 100644
index 000000000..99b1c13b0
--- /dev/null
+++ b/nuttx/arch/arm/src/samd/chip/sam_memorymap.h
@@ -0,0 +1,52 @@
+/************************************************************************************
+ * arch/arm/src/samd/chip/sam_memorymap.h
+ *
+ * Copyright (C) 2014 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_SAMD_CHIP_SAM_MEMORYMAP_H
+#define __ARCH_ARM_SRC_SAMD_CHIP_SAM_MEMORYMAP_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include <arch/samd/chip.h>
+
+#if defined(SAMD20)
+# include "chip/samd20_memorymap.h"
+#else
+# error Unrecognized SAMD architecture
+#endif
+
+#endif /* __ARCH_ARM_SRC_SAMD_CHIP_SAM_MEMORYMAP_H */
diff --git a/nuttx/arch/arm/src/samd/chip/samd20_memorymap.h b/nuttx/arch/arm/src/samd/chip/samd20_memorymap.h
new file mode 100644
index 000000000..a10041235
--- /dev/null
+++ b/nuttx/arch/arm/src/samd/chip/samd20_memorymap.h
@@ -0,0 +1,120 @@
+/********************************************************************************************
+ * arch/arm/src/samd/chip/samd20_memorymap.h
+ *
+ * Copyright (C) 2014 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_SAMD_CHIP_SAMD20_MEMORYMAP_H
+#define __ARCH_ARM_SRC_SAMD_CHIP_SAMD20_MEMORYMAP_H
+
+/********************************************************************************************
+ * Included Files
+ ********************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/********************************************************************************************
+ * Pre-processor Definitions
+ ********************************************************************************************/
+/* System Memory Map */
+
+#define SAM_FLASH_BASE 0x00000000 /* Embedded FLASH memory space (<= 256KB) */
+#define SAM_CALIB_BASE 0x00800000 /* Calibration and auxiliary space */
+#define SAM_SRAM_BASE 0x20000000 /* Embedded SRAM memory space (<= 64KB) */
+#define SAM_AHBA_BASE 0x40000000 /* AHB-APB Bridge A (64KB) */
+#define SAM_AHBB_BASE 0x41000000 /* AHB-APB Bridge B (64KB) */
+#define SAM_AHBC_BASE 0x42000000 /* AHB-APB Bridge C (64KB) */
+
+/* Calibration and Auxiliary Space */
+
+#define SAM_AUX0_BASE 0x00804000 /* AUX0 offset address */
+#define SAM_AUX1_BASE 0x00806000 /* AUX1 offset address */
+# define SAM_AUX1_AREA1 0x00806000 /* Area 1 offset address (reserved, 64 bits) */
+# define SAM_AUX1_AREA2 0x00806008 /* Area 2 Device configuration area (64 bits) */
+# define SAM_AUX1_AREA3 0x00806010 /* Area 3 offset address (reserved, 128 bits) */
+# define SAM_AUX1_AREA4 0x00806020 /* Area 4 Software calibration area (256 bits) */
+
+/* AHB-APB Bridge A */
+
+#define SAM_PAC0_BASE 0x40000000 /* Peripheral Access Controller 0 */
+#define SAM_PM_BASE 0x40000400 /* Power Manager */
+#define SAM_SYSCTRL_BASE 0x40000800 /* System Controller */
+#define SAM_GCLK_BASE 0x40000C00 /* Generic Clock Controller */
+#define SAM_WDT_BASE 0x40001000 /* Watchdog Timer */
+#define SAM_RTC_BASE 0x40001400 /* Real-Time Counter */
+#define SAM_EIC_BASE 0x40001800 /* External Interrupt Controller */
+
+/* AHB-APB Bridge B */
+
+#define SAM_PAC1_BASE 0x41000000 /* Peripheral Access Controller 1 */
+#define SAM_DSU_BASE 0x41002000 /* Device Service Unit */
+#define SAM_NVMCTRL_BASE 0x41004000 /* Non-Volatile Memory Controller */
+#define SAM_PORT_BASE 0x41004400 /* Ports */
+
+/* AHB-APB Bridge C */
+
+#define SAM_PAC2_BASE 0x42000000 /* Peripheral Access Controller 2 */
+#define SAM_EVSYS_BASE 0x42000400 /* Event System */
+#define SAM_SERCOM0_BASE 0x42000800 /* Serial Communication Interface 0 */
+#define SAM_SERCOM1_BASE 0x42000c00 /* Serial Communication Interface 1 */
+#define SAM_SERCOM2_BASE 0x42001000 /* Serial Communication Interface 2 */
+#define SAM_SERCOM3_BASE 0x42001400 /* Serial Communication Interface 3 */
+#define SAM_SERCOM4_BASE 0x42001800 /* Serial Communication Interface 4 */
+#define SAM_SERCOM5_BASE 0x42001c00 /* Serial Communication Interface 5 */
+#define SAM_TC0_BASE 0x42002000 /* Timer/Counter 0 */
+#define SAM_TC1_BASE 0x42002400 /* Timer/Counter 1 */
+#define SAM_TC2_BASE 0x42002800 /* Timer/Counter 2 */
+#define SAM_TC3_BASE 0x42002c00 /* Timer/Counter 3 */
+#define SAM_TC4_BASE 0x42003000 /* Timer/Counter 4 */
+#define SAM_TC5_BASE 0x42003400 /* Timer/Counter 5 */
+#define SAM_TC6_BASE 0x42003800 /* Timer/Counter 6 */
+#define SAM_TC7_BASE 0x42003c00 /* Timer/Counter 7 */
+#define SAM_ADC_BASE 0x42004000 /* Analog-to-Digital Converter */
+#define SAM_AC_BASE 0x42004400 /* Analog Comparator*/
+#define SAM_DAC_BASE 0x42004800 /* Digital-to-Analog Converter */
+#define SAM_PTC_BASE 0x42004C00 /* Peripheral Touch Controller */
+
+ /********************************************************************************************
+ * Public Types
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Data
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Functions
+ ********************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_SAMD_CHIP_SAMD20_MEMORYMAP_H */
diff --git a/nuttx/arch/arm/src/samd/sam_clockconfig.h b/nuttx/arch/arm/src/samd/sam_clockconfig.h
new file mode 100644
index 000000000..ee39b45eb
--- /dev/null
+++ b/nuttx/arch/arm/src/samd/sam_clockconfig.h
@@ -0,0 +1,93 @@
+/************************************************************************************
+ * arch/arm/src/samd/sam_clockconfig.h
+ *
+ * Copyright (C) 2014 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_SAMD_SAM_CLOCKCONFIG_H
+#define __ARCH_ARM_SRC_SAMD_SAM_CLOCKCONFIG_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: sam_clockconfig
+ *
+ * Description:
+ * Called to establish the clock settings based on the values in board.h.
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ ************************************************************************************/
+
+void sam_clockconfig(void);
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_ARM_SRC_SAMD_SAM_CLOCKCONFIG_H */
diff --git a/nuttx/arch/arm/src/samd/sam_config.h b/nuttx/arch/arm/src/samd/sam_config.h
new file mode 100644
index 000000000..e5b8a3941
--- /dev/null
+++ b/nuttx/arch/arm/src/samd/sam_config.h
@@ -0,0 +1,189 @@
+/************************************************************************************
+ * arch/arm/src/samd/sam_config.h
+ *
+ * Copyright (C) 2014 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_SAMD_SAM_CONFIG_H
+#define __ARCH_ARM_SRC_SAMD_SAM_CONFIG_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include <arch/samd/chip.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+/* How many SERCOM peripherals are configured as peripherals */
+
+#define SAMD_HAVE_UART0 1
+#define SAMD_HAVE_UART1 1
+#define SAMD_HAVE_UART2 1
+#define SAMD_HAVE_UART3 1
+#define SAMD_HAVE_UART4 1
+#define SAMD_HAVE_UART5 1
+
+#if !defined(CONFIG_SAMD_SERCOM0) || !defined(CONFIG_SAMD_SERCOM0_UART)
+# undef SAMD_HAVE_UART0
+# undef CONFIG_SAMD_SERCOM0_UART
+# undef CONFIG_UART0_SERIAL_CONSOLE
+# undef CONFIG_UART0_FLOW_CONTROL
+# undef CONFIG_UART0_IRDAMODE
+# undef CONFIG_UART0_RS485MODE
+#endif
+
+#if !defined(CONFIG_SAMD_SERCOM1) || !defined(CONFIG_SAMD_SERCOM1_UART)
+# undef SAMD_HAVE_UART1
+# undef CONFIG_SAMD_SERCOM1_UART
+# undef CONFIG_UART1_SERIAL_CONSOLE
+# undef CONFIG_UART1_FLOW_CONTROL
+# undef CONFIG_UART1_IRDAMODE
+# undef CONFIG_UART1_RS485MODE
+#endif
+
+#if !defined(CONFIG_SAMD_SERCOM2) || !defined(CONFIG_SAMD_SERCOM2_UART)
+# undef SAMD_HAVE_UART2
+# undef CONFIG_SAMD_SERCOM2_UART
+# undef CONFIG_UART2_SERIAL_CONSOLE
+# undef CONFIG_UART2_FLOW_CONTROL
+# undef CONFIG_UART2_IRDAMODE
+# undef CONFIG_UART2_RS485MODE
+#endif
+
+#if !defined(CONFIG_SAMD_SERCOM3) || !defined(CONFIG_SAMD_SERCOM3_UART)
+# undef SAMD_HAVE_UART3
+# undef CONFIG_SAMD_SERCOM3_UART
+# undef CONFIG_UART3_SERIAL_CONSOLE
+# undef CONFIG_UART3_FLOW_CONTROL
+# undef CONFIG_UART3_IRDAMODE
+# undef CONFIG_UART3_RS485MODE
+#endif
+
+#if !defined(CONFIG_SAMD_SERCOM4) || !defined(CONFIG_SAMD_SERCOM4_UART)
+# undef SAMD_HAVE_UART4
+# undef CONFIG_SAMD_SERCOM4_UART
+# undef CONFIG_UART4_SERIAL_CONSOLE
+# undef CONFIG_UART4_FLOW_CONTROL
+# undef CONFIG_UART4_IRDAMODE
+# undef CONFIG_UART4_RS485MODE
+#endif
+
+#if !defined(CONFIG_SAMD_SERCOM5) || !defined(CONFIG_SAMD_SERCOM5_UART)
+# undef SAMD_HAVE_UART5
+# undef CONFIG_SAMD_SERCOM5_UART
+# undef CONFIG_UART5_SERIAL_CONSOLE
+# undef CONFIG_UART5_FLOW_CONTROL
+# undef CONFIG_UART5_IRDAMODE
+# undef CONFIG_UART5_RS485MODE
+#endif
+
+/* Are any UARTs enabled? */
+
+#undef HAVE_UART
+#if defined(SAMD_HAVE_UART0) || defined(SAMD_HAVE_UART1) || \
+ defined(SAMD_HAVE_UART2) || defined(SAMD_HAVE_UART3) || \
+ defined(SAMD_HAVE_UART4) || defined(SAMD_HAVE_UART5)
+# define HAVE_UART 1
+#endif
+
+/* Is there a serial console? There should be at most one defined. It could be on
+ * any UARTn, n=0,1,2 - OR - there might not be any serial console at all.
+ */
+
+#if defined(CONFIG_UART0_SERIAL_CONSOLE)
+# undef CONFIG_UART1_SERIAL_CONSOLE
+# undef CONFIG_UART2_SERIAL_CONSOLE
+# undef CONFIG_UART3_SERIAL_CONSOLE
+# undef CONFIG_UART4_SERIAL_CONSOLE
+# undef CONFIG_UART5_SERIAL_CONSOLE
+# define HAVE_SERIAL_CONSOLE 1
+#elif defined(CONFIG_UART1_SERIAL_CONSOLE)
+# undef CONFIG_UART0_SERIAL_CONSOLE
+# undef CONFIG_UART2_SERIAL_CONSOLE
+# undef CONFIG_UART3_SERIAL_CONSOLE
+# undef CONFIG_UART4_SERIAL_CONSOLE
+# undef CONFIG_UART5_SERIAL_CONSOLE
+# define HAVE_SERIAL_CONSOLE 1
+#elif defined(CONFIG_UART2_SERIAL_CONSOLE)
+# undef CONFIG_UART0_SERIAL_CONSOLE
+# undef CONFIG_UART1_SERIAL_CONSOLE
+# undef CONFIG_UART3_SERIAL_CONSOLE
+# undef CONFIG_UART4_SERIAL_CONSOLE
+# undef CONFIG_UART5_SERIAL_CONSOLE
+# define HAVE_SERIAL_CONSOLE 1
+#elif defined(CONFIG_UART3_SERIAL_CONSOLE)
+# undef CONFIG_UART0_SERIAL_CONSOLE
+# undef CONFIG_UART1_SERIAL_CONSOLE
+# undef CONFIG_UART2_SERIAL_CONSOLE
+# undef CONFIG_UART4_SERIAL_CONSOLE
+# undef CONFIG_UART5_SERIAL_CONSOLE
+# define HAVE_SERIAL_CONSOLE 1
+#elif defined(CONFIG_UART4_SERIAL_CONSOLE)
+# undef CONFIG_UART0_SERIAL_CONSOLE
+# undef CONFIG_UART1_SERIAL_CONSOLE
+# undef CONFIG_UART2_SERIAL_CONSOLE
+# undef CONFIG_UART3_SERIAL_CONSOLE
+# undef CONFIG_UART5_SERIAL_CONSOLE
+# define HAVE_SERIAL_CONSOLE 1
+#elif defined(CONFIG_UART5_SERIAL_CONSOLE)
+# undef CONFIG_UART0_SERIAL_CONSOLE
+# undef CONFIG_UART1_SERIAL_CONSOLE
+# undef CONFIG_UART2_SERIAL_CONSOLE
+# undef CONFIG_UART3_SERIAL_CONSOLE
+# undef CONFIG_UART4_SERIAL_CONSOLE
+# define HAVE_SERIAL_CONSOLE 1
+#else
+# undef CONFIG_UART0_SERIAL_CONSOLE
+# undef CONFIG_UART1_SERIAL_CONSOLE
+# undef CONFIG_UART2_SERIAL_CONSOLE
+# undef CONFIG_UART3_SERIAL_CONSOLE
+# undef CONFIG_UART4_SERIAL_CONSOLE
+# undef CONFIG_UART5_SERIAL_CONSOLE
+# undef HAVE_SERIAL_CONSOLE
+#endif
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_SAMD_SAM_CONFIG_H */
diff --git a/nuttx/arch/arm/src/samd/sam_gpio.h b/nuttx/arch/arm/src/samd/sam_gpio.h
new file mode 100644
index 000000000..ca381e589
--- /dev/null
+++ b/nuttx/arch/arm/src/samd/sam_gpio.h
@@ -0,0 +1,146 @@
+/****************************************************************************
+ * arch/arm/src/samd/sam_gpio.h
+ *
+ * Copyright (C) 2014 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_SAMD_SAM_GPIO_H
+#define __ARCH_ARM_SRC_SAMD_SAM_GPIO_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#ifndef __ASSEMBLY__
+# include <stdint.h>
+# include <stdbool.h>
+#endif
+
+#include <nuttx/irq.h>
+
+#include "chip.h"
+#include "chip/sam_gpio.h"
+
+/****************************************************************************
+ * Pre-processor Declarations
+ ****************************************************************************/
+
+/* Bit-encoded input to sam_configgpio() */
+#warning Missing logic
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+typedef uint16_t gpio_cfgset_t;
+#warning REVISIT
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sam_configgpio
+ *
+ * Description:
+ * Configure a GPIO pin based on bit-encoded description of the pin.
+ * Once it is configured as Alternative (GPIO_ALT|GPIO_CNF_AFPP|...)
+ * function, it must be unconfigured with sam_unconfiggpio() with
+ * the same cfgset first before it can be set to non-alternative function.
+ *
+ * Returns:
+ * OK on success
+ * ERROR on invalid port, or when pin is locked as ALT function.
+ *
+ ****************************************************************************/
+
+int sam_configgpio(gpio_cfgset_t cfgset);
+
+/****************************************************************************
+ * Name: sam_gpiowrite
+ *
+ * Description:
+ * Write one or zero to the selected GPIO pin
+ *
+ ****************************************************************************/
+
+void sam_gpiowrite(gpio_cfgset_t pinset, bool value);
+
+/****************************************************************************
+ * Name: sam_gpioread
+ *
+ * Description:
+ * Read one or zero from the selected GPIO pin
+ *
+ ****************************************************************************/
+
+bool sam_gpioread(gpio_cfgset_t pinset);
+
+/****************************************************************************
+ * Function: sam_dumpgpio
+ *
+ * Description:
+ * Dump all GPIO registers associated with the provided pin description
+ * along with a descriptive message.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_DEBUG
+void sam_dumpgpio(gpio_cfgset_t pinset, const char *msg);
+#else
+# define sam_dumpgpio(p,m)
+#endif
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_ARM_SRC_SAMD_SAM_GPIO_H */
diff --git a/nuttx/arch/arm/src/samd/sam_idle.c b/nuttx/arch/arm/src/samd/sam_idle.c
new file mode 100644
index 000000000..ea18904bf
--- /dev/null
+++ b/nuttx/arch/arm/src/samd/sam_idle.c
@@ -0,0 +1,187 @@
+/****************************************************************************
+ * arch/arm/src/samd/sam_idle.c
+ *
+ * Copyright (C) 2014 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <arch/board/board.h>
+#include <nuttx/config.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/power/pm.h>
+
+#include <arch/irq.h>
+
+#include "chip.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Does the board support an IDLE LED to indicate that the board is in the
+ * IDLE state?
+ */
+
+#if defined(CONFIG_ARCH_LEDS) && defined(LED_IDLE)
+# define BEGIN_IDLE() board_led_on(LED_IDLE)
+# define END_IDLE() board_led_off(LED_IDLE)
+#else
+# define BEGIN_IDLE()
+# define END_IDLE()
+#endif
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_idlepm
+ *
+ * Description:
+ * Perform IDLE state power management.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_PM
+static void up_idlepm(void)
+{
+ static enum pm_state_e oldstate = PM_NORMAL;
+ enum pm_state_e newstate;
+ irqstate_t flags;
+ int ret;
+
+ /* Decide, which power saving level can be obtained */
+
+ newstate = pm_checkstate();
+
+ /* Check for state changes */
+
+ if (newstate != oldstate)
+ {
+ flags = irqsave();
+
+ /* Perform board-specific, state-dependent logic here */
+
+ llvdbg("newstate= %d oldstate=%d\n", newstate, oldstate);
+
+ /* Then force the global state change */
+
+ ret = pm_changestate(newstate);
+ if (ret < 0)
+ {
+ /* The new state change failed, revert to the preceding state */
+
+ (void)pm_changestate(oldstate);
+ }
+ else
+ {
+ /* Save the new state */
+
+ oldstate = newstate;
+ }
+
+ /* MCU-specific power management logic */
+
+ switch (newstate)
+ {
+ case PM_NORMAL:
+ break;
+
+ case PM_IDLE:
+ break;
+
+ case PM_STANDBY:
+ sam_pmstop(true);
+ break;
+
+ case PM_SLEEP:
+ (void)sam_pmstandby();
+ break;
+
+ default:
+ break;
+ }
+
+ irqrestore(flags);
+ }
+}
+#else
+# define up_idlepm()
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_idle
+ *
+ * Description:
+ * up_idle() is the logic that will be executed when their is no other
+ * ready-to-run task. This is processor idle time and will continue until
+ * some interrupt occurs to cause a context switch from the idle task.
+ *
+ * Processing in this state may be processor-specific. e.g., this is where
+ * power management operations might be performed.
+ *
+ ****************************************************************************/
+
+void up_idle(void)
+{
+#if defined(CONFIG_SUPPRESS_INTERRUPTS) || defined(CONFIG_SUPPRESS_TIMER_INTS)
+ /* If the system is idle and there are no timer interrupts, then process
+ * "fake" timer interrupts. Hopefully, something will wake up.
+ */
+
+ sched_process_timer();
+#else
+
+ /* Perform IDLE mode power management */
+
+ up_idlepm();
+
+ /* Sleep until an interrupt occurs to save power. */
+
+ BEGIN_IDLE();
+ asm("WFI");
+ END_IDLE();
+#endif
+}
diff --git a/nuttx/arch/arm/src/samd/sam_irq.c b/nuttx/arch/arm/src/samd/sam_irq.c
new file mode 100644
index 000000000..abbec2510
--- /dev/null
+++ b/nuttx/arch/arm/src/samd/sam_irq.c
@@ -0,0 +1,400 @@
+/****************************************************************************
+ * arch/arm/src/samd/sam_irq.c
+ *
+ * Copyright (C) 2014 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <debug.h>
+
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+#include <arch/irq.h>
+
+#include "nvic.h"
+#include "up_arch.h"
+#include "os_internal.h"
+#include "up_internal.h"
+
+#include "sam_irq.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* Get a 32-bit version of the default priority */
+
+#define DEFPRIORITY32 \
+ (NVIC_SYSH_PRIORITY_DEFAULT << 24 | NVIC_SYSH_PRIORITY_DEFAULT << 16 |\
+ NVIC_SYSH_PRIORITY_DEFAULT << 8 | NVIC_SYSH_PRIORITY_DEFAULT)
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+volatile uint32_t *current_regs;
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sam_dumpnvic
+ *
+ * Description:
+ * Dump some interesting NVIC registers
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_DEBUG_IRQ)
+static void sam_dumpnvic(const char *msg, int irq)
+{
+ irqstate_t flags;
+
+ flags = irqsave();
+
+ lldbg("NVIC (%s, irq=%d):\n", msg, irq);
+ lldbg(" ISER: %08x ICER: %08x\n",
+ getreg32(ARMV6M_NVIC_ISER), getreg32(ARMV6M_NVIC_ICER));
+ lldbg(" ISPR: %08x ICPR: %08x\n",
+ getreg32(ARMV6M_NVIC_ISPR), getreg32(ARMV6M_NVIC_ICPR));
+ lldbg(" IRQ PRIO: %08x %08x %08x %08x\n",
+ getreg32(ARMV6M_NVIC_IPR0), getreg32(ARMV6M_NVIC_IPR1),
+ getreg32(ARMV6M_NVIC_IPR2), getreg32(ARMV6M_NVIC_IPR3));
+ lldbg(" %08x %08x %08x %08x\n",
+ getreg32(ARMV6M_NVIC_IPR4), getreg32(ARMV6M_NVIC_IPR5),
+ getreg32(ARMV6M_NVIC_IPR6), getreg32(ARMV6M_NVIC_IPR7));
+
+ lldbg("SYSCON:\n");
+ lldbg(" CPUID: %08x\n",
+ getreg32(ARMV6M_SYSCON_CPUID));
+ lldbg(" ICSR: %08x AIRCR: %08x\n",
+ getreg32(ARMV6M_SYSCON_ICSR), getreg32(ARMV6M_SYSCON_AIRCR));
+ lldbg(" SCR: %08x CCR: %08x\n",
+ getreg32(ARMV6M_SYSCON_SCR), getreg32(ARMV6M_SYSCON_CCR));
+ lldbg(" SHPR2: %08x SHPR3: %08x\n",
+ getreg32(ARMV6M_SYSCON_SHPR2), getreg32(ARMV6M_SYSCON_SHPR3));
+
+ irqrestore(flags);
+}
+
+#else
+# define sam_dumpnvic(msg, irq)
+#endif
+
+/****************************************************************************
+ * Name: sam_nmi, sam_busfault, sam_usagefault, sam_pendsv,
+ * sam_dbgmonitor, sam_pendsv, sam_reserved
+ *
+ * Description:
+ * Handlers for various execptions. None are handled and all are fatal
+ * error conditions. The only advantage these provided over the default
+ * unexpected interrupt handler is that they provide a diagnostic output.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_DEBUG
+static int sam_nmi(int irq, FAR void *context)
+{
+ (void)irqsave();
+ dbg("PANIC!!! NMI received\n");
+ PANIC();
+ return 0;
+}
+
+static int sam_pendsv(int irq, FAR void *context)
+{
+ (void)irqsave();
+ dbg("PANIC!!! PendSV received\n");
+ PANIC();
+ return 0;
+}
+
+static int sam_reserved(int irq, FAR void *context)
+{
+ (void)irqsave();
+ dbg("PANIC!!! Reserved interrupt\n");
+ PANIC();
+ return 0;
+}
+#endif
+
+/****************************************************************************
+ * Name: sam_clrpend
+ *
+ * Description:
+ * Clear a pending interrupt at the NVIC.
+ *
+ ****************************************************************************/
+
+static inline void sam_clrpend(int irq)
+{
+ /* This will be called on each interrupt exit whether the interrupt can be
+ * enambled or not. So this assertion is necessarily lame.
+ */
+
+ DEBUGASSERT((unsigned)irq < NR_IRQS);
+
+ /* Check for an external interrupt */
+
+ if (irq >= SAM_IRQ_INTERRUPT && irq < SAM_IRQ_INTERRUPT + SAM_IRQ_NINTS)
+ {
+ /* Set the appropriate bit in the ISER register to enable the
+ * interrupt
+ */
+
+ putreg32((1 << (irq - SAM_IRQ_INTERRUPT)), ARMV6M_NVIC_ICPR);
+ }
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_irqinitialize
+ ****************************************************************************/
+
+void up_irqinitialize(void)
+{
+ uint32_t regaddr;
+ int i;
+
+ /* Disable all interrupts */
+
+ putreg32(0xffffffff, ARMV6M_NVIC_ICER);
+
+ /* Set all interrupts (and exceptions) to the default priority */
+
+ putreg32(DEFPRIORITY32, ARMV6M_SYSCON_SHPR2);
+ putreg32(DEFPRIORITY32, ARMV6M_SYSCON_SHPR3);
+
+ /* Now set all of the interrupt lines to the default priority */
+
+ for (i = 0; i < 8; i++)
+ {
+ regaddr = ARMV6M_NVIC_IPR(i);
+ putreg32(DEFPRIORITY32, regaddr);
+ }
+
+ /* currents_regs is non-NULL only while processing an interrupt */
+
+ current_regs = NULL;
+
+ /* Attach the SVCall and Hard Fault exception handlers. The SVCall
+ * exception is used for performing context switches; The Hard Fault
+ * must also be caught because a SVCall may show up as a Hard Fault
+ * under certain conditions.
+ */
+
+ irq_attach(SAM_IRQ_SVCALL, up_svcall);
+ irq_attach(SAM_IRQ_HARDFAULT, up_hardfault);
+
+ /* Attach all other processor exceptions (except reset and sys tick) */
+
+#ifdef CONFIG_DEBUG
+ irq_attach(SAM_IRQ_NMI, sam_nmi);
+ irq_attach(SAM_IRQ_PENDSV, sam_pendsv);
+ irq_attach(SAM_IRQ_RESERVED, sam_reserved);
+#endif
+
+ sam_dumpnvic("initial", NR_IRQS);
+
+#ifndef CONFIG_SUPPRESS_INTERRUPTS
+
+ /* And finally, enable interrupts */
+
+ irqenable();
+#endif
+}
+
+/****************************************************************************
+ * Name: up_disable_irq
+ *
+ * Description:
+ * Disable the IRQ specified by 'irq'
+ *
+ ****************************************************************************/
+
+void up_disable_irq(int irq)
+{
+ DEBUGASSERT((unsigned)irq < NR_IRQS);
+
+ /* Check for an external interrupt */
+
+ if (irq >= SAM_IRQ_INTERRUPT && irq < SAM_IRQ_INTERRUPT + SAM_IRQ_NINTS)
+ {
+ /* Set the appropriate bit in the ICER register to disable the
+ * interrupt
+ */
+
+ putreg32((1 << (irq - SAM_IRQ_INTERRUPT)), ARMV6M_NVIC_ICER);
+ }
+
+ /* Handle processor exceptions. Only SysTick can be disabled */
+
+ else if (irq == SAM_IRQ_SYSTICK)
+ {
+ modifyreg32(ARMV6M_SYSTICK_CSR, SYSTICK_CSR_ENABLE, 0);
+ }
+
+ sam_dumpnvic("disable", irq);
+}
+
+/****************************************************************************
+ * Name: up_enable_irq
+ *
+ * Description:
+ * Enable the IRQ specified by 'irq'
+ *
+ ****************************************************************************/
+
+void up_enable_irq(int irq)
+{
+ /* This will be called on each interrupt exit whether the interrupt can be
+ * enambled or not. So this assertion is necessarily lame.
+ */
+
+ DEBUGASSERT((unsigned)irq < NR_IRQS);
+
+ /* Check for external interrupt */
+
+ if (irq >= SAM_IRQ_INTERRUPT && irq < SAM_IRQ_INTERRUPT + SAM_IRQ_NINTS)
+ {
+ /* Set the appropriate bit in the ISER register to enable the
+ * interrupt
+ */
+
+ putreg32((1 << (irq - SAM_IRQ_INTERRUPT)), ARMV6M_NVIC_ISER);
+ }
+
+ /* Handle processor exceptions. Only SysTick can be disabled */
+
+ else if (irq == SAM_IRQ_SYSTICK)
+ {
+ modifyreg32(ARMV6M_SYSTICK_CSR, 0, SYSTICK_CSR_ENABLE);
+ }
+
+ sam_dumpnvic("enable", irq);
+}
+
+/****************************************************************************
+ * Name: up_ack_irq
+ *
+ * Description:
+ * Acknowledge the IRQ
+ *
+ ****************************************************************************/
+
+void up_ack_irq(int irq)
+{
+ sam_clrpend(irq);
+}
+
+/****************************************************************************
+ * 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)
+{
+ uint32_t regaddr;
+ uint32_t regval;
+ int shift;
+
+ DEBUGASSERT(irq == SAM_IRQ_SVCALL ||
+ irq == SAM_IRQ_PENDSV ||
+ irq == SAM_IRQ_SYSTICK ||
+ (irq >= SAM_IRQ_INTERRUPT && irq < NR_IRQS));
+ DEBUGASSERT(priority >= NVIC_SYSH_DISABLE_PRIORITY &&
+ priority <= NVIC_SYSH_PRIORITY_MIN);
+
+ /* Check for external interrupt */
+
+ if (irq >= SAM_IRQ_INTERRUPT && irq < SAM_IRQ_INTERRUPT + SAM_IRQ_NINTS)
+ {
+ /* ARMV6M_NVIC_IPR() maps register IPR0-IPR7 with four settings per
+ * register.
+ */
+
+ regaddr = ARMV6M_NVIC_IPR(irq >> 2);
+ shift = (irq & 3) << 3;
+ }
+
+ /* Handle processor exceptions. Only SVCall, PendSV, and SysTick can be
+ * reprioritized. And we will not permit modification of SVCall through
+ * this function.
+ */
+
+ else if (irq == SAM_IRQ_PENDSV)
+ {
+ regaddr = ARMV6M_SYSCON_SHPR2;
+ shift = SYSCON_SHPR3_PRI_14_SHIFT;
+ }
+ else if (irq == SAM_IRQ_SYSTICK)
+ {
+ regaddr = ARMV6M_SYSCON_SHPR2;
+ shift = SYSCON_SHPR3_PRI_15_SHIFT;
+ }
+ else
+ {
+ return ERROR;
+ }
+
+ /* Set the priority */
+
+ regval = getreg32(regaddr);
+ regval &= ~((uint32_t)0xff << shift);
+ regval |= ((uint32_t)priority << shift);
+ putreg32(regval, regaddr);
+
+ sam_dumpnvic("prioritize", irq);
+ return OK;
+}
+#endif
diff --git a/nuttx/arch/arm/src/samd/sam_irq.h b/nuttx/arch/arm/src/samd/sam_irq.h
new file mode 100644
index 000000000..4bcf2eeef
--- /dev/null
+++ b/nuttx/arch/arm/src/samd/sam_irq.h
@@ -0,0 +1,65 @@
+/************************************************************************************
+ * arch/arm/src/samd/sam_irq.h
+ *
+ * Copyright (C) 2014 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_SAMD_SAM_IRQ_H
+#define __ARCH_ARM_SRC_SAMD_SAM_IRQ_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Inline Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_SAMD_SAM_IRQ_H */
diff --git a/nuttx/arch/arm/src/samd/sam_lowputc.h b/nuttx/arch/arm/src/samd/sam_lowputc.h
new file mode 100644
index 000000000..9d0429e96
--- /dev/null
+++ b/nuttx/arch/arm/src/samd/sam_lowputc.h
@@ -0,0 +1,112 @@
+/************************************************************************************
+ * arch/arm/src/samd/sam_lowputc.h
+ *
+ * Copyright (C) 2014 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_SAMD_SAM_LOWPUTC_H
+#define __ARCH_ARM_SRC_SAMD_SAM_LOWPUTC_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include "sam_config.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: sam_lowsetup
+ *
+ * Description:
+ * Called at the very beginning of _start. Performs low level initialization.
+ *
+ ************************************************************************************/
+
+void sam_lowsetup(void);
+
+/****************************************************************************
+ * Name: sam_setbaud
+ *
+ * Description:
+ * Set the BAUD divisor for the selected UART.
+ *
+ *****************************************************************************/
+
+#ifdef HAVE_UART
+void sam_setbaud(uintptr_t base, uint32_t baud);
+#endif
+
+/****************************************************************************
+ * Name: sam_lowputc
+ *
+ * Description:
+ * Output one character to the UART using a simple polling method.
+ *
+ *****************************************************************************/
+
+#ifdef HAVE_SERIAL_CONSOLE
+void sam_lowputc(uint32_t ch);
+#endif
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_ARM_SRC_SAMD_SAM_LOWPUTC_H */
diff --git a/nuttx/arch/arm/src/samd/sam_serial.h b/nuttx/arch/arm/src/samd/sam_serial.h
new file mode 100644
index 000000000..0afd1b249
--- /dev/null
+++ b/nuttx/arch/arm/src/samd/sam_serial.h
@@ -0,0 +1,68 @@
+/************************************************************************************
+ * arch/arm/src/samd/sam_serial.h
+ *
+ * Copyright (C) 2014 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_SAMD_SAM_SERIAL_H
+#define __ARCH_ARM_SRC_SAMD_SAM_SERIAL_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "sam_config.h"
+#include "chip/sam_sercom.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Inline Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_SAMD_SAM_SERIAL_H */
diff --git a/nuttx/arch/arm/src/samd/sam_start.c b/nuttx/arch/arm/src/samd/sam_start.c
new file mode 100644
index 000000000..81e4cf0c2
--- /dev/null
+++ b/nuttx/arch/arm/src/samd/sam_start.c
@@ -0,0 +1,179 @@
+/****************************************************************************
+ * arch/arm/src/samd/sam_start.c
+ *
+ * Copyright (C) 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <assert.h>
+#include <debug.h>
+
+#include <nuttx/init.h>
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "up_internal.h"
+
+#include "sam_config.h"
+#include "sam_lowputc.h"
+#include "sam_clockconfig.h"
+#include "sam_userspace.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Memory Map:
+ *
+ * 0x0000:0000 - Beginning of FLASH. Address of exception vectors.
+ * 0x0003:ffff - End of flash (assuming 256KB of FLASH)
+ * 0x2000:0000 - Start of SRAM and start of .data (_sdata)
+ * - End of .data (_edata) abd start of .bss (_sbss)
+ * - End of .bss (_ebss) and bottom of idle stack
+ * - _ebss + CONFIG_IDLETHREAD_STACKSIZE = end of idle stack,
+ * start of heap
+ * 0x2000:ffff - End of SRAM and end of heap (assuming 64KB of SRAM)
+ */
+
+#define IDLE_STACK ((uint32_t)&_ebss+CONFIG_IDLETHREAD_STACKSIZE-4)
+#define HEAP_BASE ((uint32_t)&_ebss+CONFIG_IDLETHREAD_STACKSIZE)
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+const uint32_t g_idle_topstack = IDLE_STACK;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: showprogress
+ *
+ * Description:
+ * Print a character on the UART to show boot status.
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_DEBUG) && defined(HAVE_SERIAL_CONSOLE)
+# define showprogress(c) sam_lowputc((uint32_t)c)
+#else
+# define showprogress(c)
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: _start
+ *
+ * Description:
+ * This is the reset entry point.
+ *
+ ****************************************************************************/
+
+void __start(void)
+{
+ const uint32_t *src;
+ uint32_t *dest;
+
+ /* Configure the uart so that we can get debug output as soon as possible */
+
+ sam_clockconfig();
+ sam_lowsetup();
+ showprogress('A');
+
+ /* Clear .bss. We'll do this inline (vs. calling memset) just to be
+ * certain that there are no issues with the state of global variables.
+ */
+
+ for (dest = &_sbss; dest < &_ebss; )
+ {
+ *dest++ = 0;
+ }
+
+ showprogress('B');
+
+ /* Move the initialized data section from his temporary holding spot in
+ * FLASH into the correct place in SRAM. The correct place in SRAM is
+ * give by _sdata and _edata. The temporary location is in FLASH at the
+ * end of all of the other read-only data (.text, .rodata) at _eronly.
+ */
+
+ for (src = &_eronly, dest = &_sdata; dest < &_edata; )
+ {
+ *dest++ = *src++;
+ }
+
+ showprogress('C');
+
+ /* Perform early serial initialization */
+
+#ifdef USE_EARLYSERIALINIT
+ up_earlyserialinit();
+#endif
+ showprogress('D');
+
+ /* For the case of the separate user-/kernel-space build, perform whatever
+ * platform specific initialization of the user memory is required.
+ * Normally this just means initializing the user space .data and .bss
+ * segments.
+ */
+
+#ifdef CONFIG_NUTTX_KERNEL
+ sam_userspace();
+ showprogress('E');
+#endif
+
+ /* Initialize onboard resources */
+
+ sam_boardinitialize();
+ showprogress('F');
+
+ /* Then start NuttX */
+
+ showprogress('\r');
+ showprogress('\n');
+ os_start();
+
+ /* Shoulnd't get here */
+
+ for(;;);
+}
diff --git a/nuttx/arch/arm/src/samd/sam_timerisr.c b/nuttx/arch/arm/src/samd/sam_timerisr.c
new file mode 100644
index 000000000..dad9f0812
--- /dev/null
+++ b/nuttx/arch/arm/src/samd/sam_timerisr.c
@@ -0,0 +1,147 @@
+/****************************************************************************
+ * arch/arm/src/samd/sam_timerisr.c
+ *
+ * Copyright (C) 2014 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <time.h>
+#include <debug.h>
+#include <nuttx/arch.h>
+#include <arch/board/board.h>
+
+#include "nvic.h"
+#include "clock_internal.h"
+#include "up_internal.h"
+#include "up_arch.h"
+
+#include "chip.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* The desired timer interrupt frequency is 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).
+ *
+ * Then, for example, if the CPU clock is the the SysTick and BOARD_CPU_FREQUENCY is 48MHz and CLK_TCK is 100, then the reload value would be:
+ *
+ * SYSTICK_RELOAD = (48,000,000 / 100) - 1
+ * = 479,999
+ * = 0x752ff
+ *
+ * Which fits within the maximum 24-bit reload value.
+ */
+
+#define SYSTICK_RELOAD ((BOARD_CPU_FREQUENCY / CLK_TCK) - 1)
+
+/* The size of the reload field is 24 bits. Verify that the reload value
+ * will fit in the reload register.
+ */
+
+#if SYSTICK_RELOAD > 0x00ffffff
+# error SYSTICK_RELOAD exceeds the range of the RELOAD register
+#endif
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * 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)
+{
+ /* Process timer interrupt */
+
+ sched_process_timer();
+ return 0;
+}
+
+/****************************************************************************
+ * Function: up_timerinit
+ *
+ * Description:
+ * This function is called during start-up to initialize
+ * the timer interrupt.
+ *
+ ****************************************************************************/
+
+void up_timerinit(void)
+{
+ uint32_t regval;
+
+ /* Set the SysTick interrupt to the default priority */
+
+ regval = getreg32(ARMV6M_SYSCON_SHPR3);
+ regval &= ~SYSCON_SHPR3_PRI_15_MASK;
+ regval |= (NVIC_SYSH_PRIORITY_DEFAULT << SYSCON_SHPR3_PRI_15_SHIFT);
+ putreg32(regval, ARMV6M_SYSCON_SHPR3);
+
+ /* Configure SysTick to interrupt at the requested rate */
+
+ putreg32(SYSTICK_RELOAD, ARMV6M_SYSTICK_RVR);
+
+ /* Attach the timer interrupt vector */
+
+ (void)irq_attach(SAM_IRQ_SYSTICK, (xcpt_t)up_timerisr);
+
+ /* Enable SysTick interrupts */
+
+ putreg32((SYSTICK_CSR_TICKINT | SYSTICK_CSR_ENABLE), ARMV6M_SYSTICK_CSR);
+
+ /* And enable the timer interrupt */
+
+ up_enable_irq(SAM_IRQ_SYSTICK);
+}
diff --git a/nuttx/arch/arm/src/samd/sam_userspace.c b/nuttx/arch/arm/src/samd/sam_userspace.c
new file mode 100644
index 000000000..71bbb1ba3
--- /dev/null
+++ b/nuttx/arch/arm/src/samd/sam_userspace.c
@@ -0,0 +1,113 @@
+/****************************************************************************
+ * arch/arm/src/samd/sam_userspace.c
+ *
+ * Copyright (C) 2014 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <assert.h>
+
+#include <nuttx/userspace.h>
+
+#include "sam_userspace.h"
+
+#ifdef CONFIG_NUTTX_KERNEL
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sam_userspace
+ *
+ * Description:
+ * For the case of the separate user-/kernel-space build, perform whatever
+ * platform specific initialization of the user memory is required.
+ * Normally this just means initializing the user space .data and .bss
+ * segments.
+ *
+ ****************************************************************************/
+
+void sam_userspace(void)
+{
+ uint8_t *src;
+ uint8_t *dest;
+ uint8_t *end;
+
+ /* Clear all of user-space .bss */
+
+ DEBUGASSERT(USERSPACE->us_bssstart != 0 && USERSPACE->us_bssend != 0 &&
+ USERSPACE->us_bssstart <= USERSPACE->us_bssend);
+
+ dest = (uint8_t*)USERSPACE->us_bssstart;
+ end = (uint8_t*)USERSPACE->us_bssend;
+
+ while (dest != end)
+ {
+ *dest++ = 0;
+ }
+
+ /* Initialize all of user-space .data */
+
+ DEBUGASSERT(USERSPACE->us_datasource != 0 &&
+ USERSPACE->us_datastart != 0 && USERSPACE->us_dataend != 0 &&
+ USERSPACE->us_datastart <= USERSPACE->us_dataend);
+
+ src = (uint8_t*)USERSPACE->us_datasource;
+ dest = (uint8_t*)USERSPACE->us_datastart;
+ end = (uint8_t*)USERSPACE->us_dataend;
+
+ while (dest != end)
+ {
+ *dest++ = *src++;
+ }
+}
+
+#endif /* CONFIG_NUTTX_KERNEL */
diff --git a/nuttx/arch/arm/src/samd/sam_userspace.h b/nuttx/arch/arm/src/samd/sam_userspace.h
new file mode 100644
index 000000000..922aed1db
--- /dev/null
+++ b/nuttx/arch/arm/src/samd/sam_userspace.h
@@ -0,0 +1,76 @@
+/************************************************************************************
+ * arch/arm/src/samd/sam_userspace.h
+ *
+ * Copyright (C) 2014 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_SAMD_SAM_USERSPACE_H
+#define __ARCH_ARM_SRC_SAMD_SAM_USERSPACE_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/****************************************************************************
+ * Name: sam_userspace
+ *
+ * Description:
+ * For the case of the separate user-/kernel-space build, perform whatever
+ * platform specific initialization of the user memory is required.
+ * Normally this just means initializing the user space .data and .bss
+ * segments.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NUTTX_KERNEL
+void sam_userspace(void);
+#endif
+
+#endif /* __ARCH_ARM_SRC_SAMD_SAM_USERSPACE_H */