summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2015-03-06 10:53:57 -0600
committerGregory Nutt <gnutt@nuttx.org>2015-03-06 10:53:57 -0600
commita123507848fac3e1b120b6fd5f581aacfe477fd2 (patch)
tree80b072fef97ca633c8bb270933059571525edf22 /nuttx
parent7c84fcdc95745870d6ea40c04df69e61a32b22df (diff)
downloadpx4-nuttx-a123507848fac3e1b120b6fd5f581aacfe477fd2.tar.gz
px4-nuttx-a123507848fac3e1b120b6fd5f581aacfe477fd2.tar.bz2
px4-nuttx-a123507848fac3e1b120b6fd5f581aacfe477fd2.zip
Cortex-M7/SAMV71-XULT: Various fixes for building Cortex-M7 with SAMV71.
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/arm/include/irq.h3
-rw-r--r--nuttx/arch/arm/src/Makefile4
-rw-r--r--nuttx/arch/arm/src/armv7-m/Toolchain.defs13
-rw-r--r--nuttx/arch/arm/src/common/up_internal.h13
-rw-r--r--nuttx/arch/arm/src/common/up_vfork.c2
-rw-r--r--nuttx/arch/arm/src/samv7/chip.h77
-rw-r--r--nuttx/arch/arm/src/samv7/sam_clockconfig.h94
-rw-r--r--nuttx/arch/arm/src/samv7/sam_lowputc.h114
-rw-r--r--nuttx/arch/arm/src/samv7/sam_start.c8
-rw-r--r--nuttx/arch/arm/src/samv7/sam_start.h114
-rw-r--r--nuttx/arch/arm/src/samv7/sam_userspace.h105
-rw-r--r--nuttx/configs/sam4e-ek/include/board.h12
-rw-r--r--nuttx/configs/samv71-xult/include/board.h61
-rw-r--r--nuttx/configs/samv71-xult/nsh/defconfig5
-rwxr-xr-xnuttx/configs/samv71-xult/nsh/setenv.sh8
15 files changed, 603 insertions, 30 deletions
diff --git a/nuttx/arch/arm/include/irq.h b/nuttx/arch/arm/include/irq.h
index 27b39f95b..973ea0265 100644
--- a/nuttx/arch/arm/include/irq.h
+++ b/nuttx/arch/arm/include/irq.h
@@ -58,7 +58,8 @@
#if defined(CONFIG_ARCH_CORTEXA5) || defined(CONFIG_ARCH_CORTEXA8)
# include <arch/armv7-a/irq.h>
-#elif defined(CONFIG_ARCH_CORTEXM3) || defined(CONFIG_ARCH_CORTEXM4)
+#elif defined(CONFIG_ARCH_CORTEXM3) || defined(CONFIG_ARCH_CORTEXM4) || \
+ defined(CONFIG_ARCH_CORTEXM7)
# include <arch/armv7-m/irq.h>
#elif defined(CONFIG_ARCH_CORTEXM0)
# include <arch/armv6-m/irq.h>
diff --git a/nuttx/arch/arm/src/Makefile b/nuttx/arch/arm/src/Makefile
index 40e7973ca..728c29648 100644
--- a/nuttx/arch/arm/src/Makefile
+++ b/nuttx/arch/arm/src/Makefile
@@ -36,7 +36,7 @@
-include $(TOPDIR)/Make.defs
-include chip/Make.defs
-ifeq ($(CONFIG_ARCH_CORTEXA5),y) # Cortex-A5 is ARMv7-A
+ifeq ($(CONFIG_ARCH_CORTEXA5),y) # Cortex-A5 is ARMv7-A
ARCH_SUBDIR = armv7-a
else ifeq ($(CONFIG_ARCH_CORTEXA8),y) # Cortex-A8 is ARMv7-A
ARCH_SUBDIR = armv7-a
@@ -48,7 +48,7 @@ else ifeq ($(CONFIG_ARCH_CORTEXM7),y) # Cortex-M4 is ARMv7E-M
ARCH_SUBDIR = armv7-m
else ifeq ($(CONFIG_ARCH_CORTEXM0),y) # Cortex-M0 is ARMv6-M
ARCH_SUBDIR = armv6-m
-else
+else # ARM9, ARM7TDMI
ARCH_SUBDIR = arm
endif
diff --git a/nuttx/arch/arm/src/armv7-m/Toolchain.defs b/nuttx/arch/arm/src/armv7-m/Toolchain.defs
index 1015a8598..e571ee68a 100644
--- a/nuttx/arch/arm/src/armv7-m/Toolchain.defs
+++ b/nuttx/arch/arm/src/armv7-m/Toolchain.defs
@@ -134,11 +134,14 @@ ifeq ($(CONFIG_ARCH_CORTEXM4),y)
endif
else ifeq ($(CONFIG_ARCH_CORTEXM7),y)
TOOLCHAIN_ARM7EM := y
- TOOLCHAIN_MCPU := -mcpu=cortex-m7
- TOOLCHAIN_MTUNE := -mtune=cortex-m7
+ # FIXME: Most tools do not yet support the cortex-m7 CPU type
+ # TOOLCHAIN_MCPU := -mcpu=cortex-m7
+ # TOOLCHAIN_MTUNE := -mtune=cortex-m7
+ TOOLCHAIN_MCPU := -mcpu=cortex-m4
+ TOOLCHAIN_MTUNE := -mtune=cortex-m4
TOOLCHAIN_MARCH := -march=armv7e-m
ifeq ($(CONFIG_ARCH_FPU),y)
- #TOOLCHAIN_MFLOAT := -mfpu=fpv5-sp-d16 -mfloat-abi=hard # Single precision
+ # TOOLCHAIN_MFLOAT := -mfpu=fpv5-sp-d16 -mfloat-abi=hard # Single precision
TOOLCHAIN_MFLOAT := -mfpu=fpv5-d16 -mfloat-abi=hard
else
TOOLCHAIN_MFLOAT := -mfloat-abi=soft
@@ -223,8 +226,8 @@ endif
# devkitARM under Windows
ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),DEVKITARM)
- CROSSDEV ?= arm-eabi-
- ARCROSSDEV ?= arm-eabi-
+ CROSSDEV ?= arm-none-eabi-
+ ARCROSSDEV ?= arm-none-eabi-
ifneq ($(CONFIG_WINDOWS_NATIVE),y)
WINTOOL = y
endif
diff --git a/nuttx/arch/arm/src/common/up_internal.h b/nuttx/arch/arm/src/common/up_internal.h
index 3f417374d..3ebd15094 100644
--- a/nuttx/arch/arm/src/common/up_internal.h
+++ b/nuttx/arch/arm/src/common/up_internal.h
@@ -119,7 +119,7 @@
*/
#if defined(CONFIG_ARCH_CORTEXM0) || defined(CONFIG_ARCH_CORTEXM3) || \
- defined(CONFIG_ARCH_CORTEXM4)
+ defined(CONFIG_ARCH_CORTEXM4) || defined(CONFIG_ARCH_CORTEXM7)
/* If the floating point unit is present and enabled, then save the
* floating point registers as well as normal ARM registers. This only
@@ -317,7 +317,7 @@ void up_pminitialize(void);
#endif
#if defined(CONFIG_ARCH_CORTEXM0) || defined(CONFIG_ARCH_CORTEXM3) || \
- defined(CONFIG_ARCH_CORTEXM4)
+ defined(CONFIG_ARCH_CORTEXM4) || defined(CONFIG_ARCH_CORTEXM7)
void up_systemreset(void) noreturn_function;
#endif
@@ -328,7 +328,7 @@ void up_irqinitialize(void);
/* Exception handling logic unique to the Cortex-M family */
#if defined(CONFIG_ARCH_CORTEXM0) || defined(CONFIG_ARCH_CORTEXM3) || \
- defined(CONFIG_ARCH_CORTEXM4)
+ defined(CONFIG_ARCH_CORTEXM4) || defined(CONFIG_ARCH_CORTEXM7)
/* Interrupt acknowledge and dispatch */
@@ -340,11 +340,12 @@ uint32_t *up_doirq(int irq, uint32_t *regs);
int up_svcall(int irq, FAR void *context);
int up_hardfault(int irq, FAR void *context);
-# if defined(CONFIG_ARCH_CORTEXM3) || defined(CONFIG_ARCH_CORTEXM4)
+# if defined(CONFIG_ARCH_CORTEXM3) || defined(CONFIG_ARCH_CORTEXM4) || \
+ defined(CONFIG_ARCH_CORTEXM7)
int up_memfault(int irq, FAR void *context);
-# endif /* CONFIG_ARCH_CORTEXM3 || CONFIG_ARCH_CORTEXM4 */
+# endif /* CONFIG_ARCH_CORTEXM3,4,7 */
/* Exception handling logic unique to the Cortex-A family (but should be
* back-ported to the ARM7 and ARM9 families).
@@ -398,7 +399,7 @@ void up_prefetchabort(uint32_t *regs);
void up_syscall(uint32_t *regs);
void up_undefinedinsn(uint32_t *regs);
-#endif /* CONFIG_ARCH_CORTEXM0 || CONFIG_ARCH_CORTEXM3 || CONFIG_ARCH_CORTEXM4 */
+#endif /* CONFIG_ARCH_CORTEXM0,3,4,7 */
void up_vectorundefinsn(void);
void up_vectorswi(void);
diff --git a/nuttx/arch/arm/src/common/up_vfork.c b/nuttx/arch/arm/src/common/up_vfork.c
index 801ac1f67..df7e770c1 100644
--- a/nuttx/arch/arm/src/common/up_vfork.c
+++ b/nuttx/arch/arm/src/common/up_vfork.c
@@ -249,7 +249,7 @@ pid_t up_vfork(const struct vfork_s *context)
parent->xcp.syscall[index].cpsr;
#elif defined(CONFIG_ARCH_CORTEXM3) || defined(CONFIG_ARCH_CORTEXM4) || \
- defined(CONFIG_ARCH_CORTEXM0)
+ defined(CONFIG_ARCH_CORTEXM0) || defined(CONFIG_ARCH_CORTEXM7)
child->cmn.xcp.syscall[index].excreturn =
parent->xcp.syscall[index].excreturn;
diff --git a/nuttx/arch/arm/src/samv7/chip.h b/nuttx/arch/arm/src/samv7/chip.h
new file mode 100644
index 000000000..aa799c733
--- /dev/null
+++ b/nuttx/arch/arm/src/samv7/chip.h
@@ -0,0 +1,77 @@
+/************************************************************************************
+ * arch/arm/src/samv7/chip.h
+ *
+ * Copyright (C) 2015 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_SAMV7_CHIP_H
+#define __ARCH_ARM_SRC_SAMV7_CHIP_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/* Include the memory map and the chip definitions file. Other chip hardware files
+ * should then include this file for the proper setup.
+ */
+
+#include <arch/irq.h>
+#include <arch/samv7/chip.h>
+#include "chip/sam_memorymap.h"
+
+/* If the common ARMv7-M vector handling logic is used, then it expects
+ * the following definition in this file that provides the number of
+ * supported vectors external interrupts (which for the SAMV7 is the same
+ * as the number of peripheral identifiers).
+ */
+
+#define ARMV7M_PERIPHERAL_INTERRUPTS NR_PIDS
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_SAMV7_CHIP_H */
diff --git a/nuttx/arch/arm/src/samv7/sam_clockconfig.h b/nuttx/arch/arm/src/samv7/sam_clockconfig.h
new file mode 100644
index 000000000..44f5e0562
--- /dev/null
+++ b/nuttx/arch/arm/src/samv7/sam_clockconfig.h
@@ -0,0 +1,94 @@
+/************************************************************************************
+ * arch/arm/src/samv7/sam_clockconfig.h
+ *
+ * Copyright (C) 2015 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_SAMV7_SAM_CLOCKCONFIG_H
+#define __ARCH_ARM_SRC_SAMV7_SAM_CLOCKCONFIG_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Inline Functions
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+/************************************************************************************
+ * Public Function Prototypes
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: sam_clockconfig
+ *
+ * Description:
+ * Called to initialize the SAM3/4. This does whatever setup is needed to put the
+ * SoC in a usable state. This includes the initialization of clocking using the
+ * settings in board.h.
+ *
+ ************************************************************************************/
+
+void sam_clockconfig(void);
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_ARM_SRC_SAMV7_SAM_CLOCKCONFIG_H */
diff --git a/nuttx/arch/arm/src/samv7/sam_lowputc.h b/nuttx/arch/arm/src/samv7/sam_lowputc.h
new file mode 100644
index 000000000..dcd256036
--- /dev/null
+++ b/nuttx/arch/arm/src/samv7/sam_lowputc.h
@@ -0,0 +1,114 @@
+/************************************************************************************
+ * arch/arm/src/samv7/sam_lowputc.h
+ *
+ * Copyright (C) 2015 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_SAMV7_SAM_LOWPUTC_H
+#define __ARCH_ARM_SRC_SAMV7_SAM_LOWPUTC_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/compiler.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+
+#include "up_internal.h"
+#include "chip.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Inline Functions
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+/************************************************************************************
+ * Public Function Prototypes
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: sam_lowsetup
+ *
+ * Description:
+ * Called at the very beginning of _start. Performs low level initialization
+ * including setup of the console UART. This UART done early so that the serial
+ * console is available for debugging very early in the boot sequence.
+ *
+ ************************************************************************************/
+
+void sam_lowsetup(void);
+
+/************************************************************************************
+ * Name: sam_boardinitialize
+ *
+ * Description:
+ * All SAMV7 architectures must provide the following entry point. This entry
+ * point is called early in the initialization -- after all memory has been
+ * configured and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+void sam_boardinitialize(void);
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_ARM_SRC_SAMV7_SAM_LOWPUTC_H */
diff --git a/nuttx/arch/arm/src/samv7/sam_start.c b/nuttx/arch/arm/src/samv7/sam_start.c
index afbfe80b8..592c67cec 100644
--- a/nuttx/arch/arm/src/samv7/sam_start.c
+++ b/nuttx/arch/arm/src/samv7/sam_start.c
@@ -49,14 +49,14 @@
#include "up_arch.h"
#include "up_internal.h"
-#include "sam_clockconfig.h"
-#include "sam_lowputc.h"
-#include "sam_userspace.h"
-
#ifdef CONFIG_ARCH_FPU
# include "nvic.h"
#endif
+#include "sam_clockconfig.h"
+#include "sam_userspace.h"
+#include "sam_start.h"
+
/****************************************************************************
* Private Function prototypes
****************************************************************************/
diff --git a/nuttx/arch/arm/src/samv7/sam_start.h b/nuttx/arch/arm/src/samv7/sam_start.h
new file mode 100644
index 000000000..1769021e5
--- /dev/null
+++ b/nuttx/arch/arm/src/samv7/sam_start.h
@@ -0,0 +1,114 @@
+/************************************************************************************
+ * arch/arm/src/samv7/sam_start.h
+ *
+ * Copyright (C) 2015 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_SAMV7_SAM_START_H
+#define __ARCH_ARM_SRC_SAMV7_SAM_START_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/compiler.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+
+#include "up_internal.h"
+#include "chip.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Inline Functions
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+/************************************************************************************
+ * Public Function Prototypes
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: sam_lowsetup
+ *
+ * Description:
+ * Called at the very beginning of _start. Performs low level initialization
+ * including setup of the console UART. This UART done early so that the serial
+ * console is available for debugging very early in the boot sequence.
+ *
+ ************************************************************************************/
+
+void sam_lowsetup(void);
+
+/************************************************************************************
+ * Name: sam_boardinitialize
+ *
+ * Description:
+ * All SAMV7 architectures must provide the following entry point. This entry
+ * point is called early in the initialization -- after all memory has been
+ * configured and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+void sam_boardinitialize(void);
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_ARM_SRC_SAMV7_SAM_START_H */
diff --git a/nuttx/arch/arm/src/samv7/sam_userspace.h b/nuttx/arch/arm/src/samv7/sam_userspace.h
new file mode 100644
index 000000000..1af2b476f
--- /dev/null
+++ b/nuttx/arch/arm/src/samv7/sam_userspace.h
@@ -0,0 +1,105 @@
+/************************************************************************************
+ * arch/arm/src/samv7/sam_userspace.h
+ *
+ * Copyright (C) 2015 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_SAMV7_SAM_USERSPACE_H
+#define __ARCH_ARM_SRC_SAMV7_SAM_USERSPACE_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/compiler.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+
+#include "up_internal.h"
+#include "chip.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Inline Functions
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+/************************************************************************************
+ * Public Function Prototypes
+ ************************************************************************************/
+
+/****************************************************************************
+ * 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_BUILD_PROTECTED
+void sam_userspace(void);
+#endif
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_ARM_SRC_SAMV7_SAM_USERSPACE_H */
diff --git a/nuttx/configs/sam4e-ek/include/board.h b/nuttx/configs/sam4e-ek/include/board.h
index 68e74a3f5..9bc48258c 100644
--- a/nuttx/configs/sam4e-ek/include/board.h
+++ b/nuttx/configs/sam4e-ek/include/board.h
@@ -286,7 +286,7 @@ extern "C" {
* Name: sam_boardinitialize
*
* Description:
- * All SAM3U architectures must provide the following entry point. This entry point
+ * All SAM4E architectures must provide the following entry point. This entry point
* is called early in the initialization -- after all memory has been configured
* and mapped but before any devices have been initialized.
*
@@ -294,11 +294,6 @@ extern "C" {
void sam_boardinitialize(void);
-#undef EXTERN
-#if defined(__cplusplus)
-}
-#endif
-
/************************************************************************************
* Name: sam_ledinit, sam_setled, and sam_setleds
*
@@ -332,5 +327,10 @@ void sam_lcdclear(uint16_t color);
void sam_lcdclear(uint32_t color);
#endif
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_SAM4E_EK_INCLUDE_BOARD_H */
diff --git a/nuttx/configs/samv71-xult/include/board.h b/nuttx/configs/samv71-xult/include/board.h
new file mode 100644
index 000000000..1273487a5
--- /dev/null
+++ b/nuttx/configs/samv71-xult/include/board.h
@@ -0,0 +1,61 @@
+/************************************************************************************
+ * configs/samv71-xult/include/board.h
+ *
+ * Copyright (C) 2015 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 __CONFIGS_SAMV71_XULT_INCLUDE_BOARD_H
+#define __CONFIGS_SAMV71_XULT_INCLUDE_BOARD_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __CONFIGS_SAMV71_XULT_INCLUDE_BOARD_H */
diff --git a/nuttx/configs/samv71-xult/nsh/defconfig b/nuttx/configs/samv71-xult/nsh/defconfig
index 3faefef34..83698f0b8 100644
--- a/nuttx/configs/samv71-xult/nsh/defconfig
+++ b/nuttx/configs/samv71-xult/nsh/defconfig
@@ -283,11 +283,10 @@ CONFIG_ARCH_BOARD="samv71-xult"
# Common Board Options
#
CONFIG_ARCH_HAVE_LEDS=y
-CONFIG_ARCH_LEDS=y
+# CONFIG_ARCH_LEDS is not set
CONFIG_ARCH_HAVE_BUTTONS=y
-CONFIG_ARCH_BUTTONS=y
+# CONFIG_ARCH_BUTTONS is not set
CONFIG_ARCH_HAVE_IRQBUTTONS=y
-# CONFIG_ARCH_IRQBUTTONS is not set
CONFIG_NSH_MMCSDMINOR=0
#
diff --git a/nuttx/configs/samv71-xult/nsh/setenv.sh b/nuttx/configs/samv71-xult/nsh/setenv.sh
index 57f2f3609..1174f12bc 100755
--- a/nuttx/configs/samv71-xult/nsh/setenv.sh
+++ b/nuttx/configs/samv71-xult/nsh/setenv.sh
@@ -51,7 +51,7 @@ fi
# toolchain under Windows. You will also have to edit this if you install
# this toolchain in any other location
#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
-#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
+export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
# This is the Cygwin path to the location where I installed the CodeSourcery
@@ -59,9 +59,13 @@ fi
# the CodeSourcery toolchain in any other location
#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
+# This is the path to the location where I installed the devkitARM toolchain
+# You an get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
+# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
+
# This is the Cygwin path to the location where I build the buildroot
# toolchain.
-export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
+# export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
# Add the path to the toolchain to the PATH varialble
export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"