summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--NxWidgets/ChangeLog.txt1
-rw-r--r--nuttx/ChangeLog10
-rw-r--r--nuttx/arch/arm/Kconfig3
-rw-r--r--nuttx/arch/arm/src/arm/Kconfig35
-rw-r--r--nuttx/arch/arm/src/arm/Toolchain.defs146
-rw-r--r--nuttx/arch/arm/src/armv7-m/Toolchain.defs30
-rw-r--r--nuttx/arch/avr/Kconfig42
-rw-r--r--nuttx/arch/avr/src/avr/Kconfig53
-rw-r--r--nuttx/arch/avr/src/avr/Toolchain.defs117
-rw-r--r--nuttx/arch/avr/src/avr32/Kconfig3
-rw-r--r--nuttx/arch/avr/src/avr32/Toolchain.defs63
-rw-r--r--nuttx/arch/mips/src/mips32/Toolchain.defs38
-rw-r--r--nuttx/configs/amber/README.txt14
-rw-r--r--nuttx/configs/amber/hello/Make.defs28
-rw-r--r--nuttx/configs/avr32dev1/README.txt12
-rw-r--r--nuttx/configs/avr32dev1/nsh/Make.defs15
-rw-r--r--nuttx/configs/ea3131/README.txt28
-rw-r--r--nuttx/configs/ea3131/nsh/Make.defs25
-rw-r--r--nuttx/configs/ea3131/ostest/Make.defs25
-rw-r--r--nuttx/configs/ea3131/pgnsh/Make.defs25
-rw-r--r--nuttx/configs/ea3131/usbserial/Make.defs25
-rw-r--r--nuttx/configs/ea3131/usbstorage/Make.defs25
-rw-r--r--nuttx/configs/ea3152/README.txt28
-rw-r--r--nuttx/configs/ea3152/ostest/Make.defs25
-rw-r--r--nuttx/configs/micropendous3/README.txt16
-rw-r--r--nuttx/configs/micropendous3/hello/Make.defs28
-rw-r--r--nuttx/configs/mirtoo/README.txt15
-rw-r--r--nuttx/configs/ntosd-dm320/README.txt28
-rw-r--r--nuttx/configs/ntosd-dm320/nettest/Make.defs25
-rw-r--r--nuttx/configs/ntosd-dm320/nsh/Make.defs25
-rw-r--r--nuttx/configs/ntosd-dm320/ostest/Make.defs25
-rw-r--r--nuttx/configs/ntosd-dm320/poll/Make.defs25
-rw-r--r--nuttx/configs/ntosd-dm320/thttpd/Make.defs25
-rw-r--r--nuttx/configs/ntosd-dm320/udp/Make.defs25
-rw-r--r--nuttx/configs/ntosd-dm320/uip/Make.defs25
-rw-r--r--nuttx/configs/olimex-lpc2378/nsh/Make.defs25
-rw-r--r--nuttx/configs/olimex-lpc2378/ostest/Make.defs25
-rw-r--r--nuttx/configs/stm3220g-eval/README.txt33
-rw-r--r--nuttx/configs/teensy/README.txt16
-rw-r--r--nuttx/configs/teensy/hello/Make.defs28
-rw-r--r--nuttx/configs/teensy/nsh/Make.defs28
-rw-r--r--nuttx/configs/teensy/usbstorage/Make.defs28
-rwxr-xr-xnuttx/tools/incdir.bat56
-rwxr-xr-xnuttx/tools/incdir.sh37
44 files changed, 731 insertions, 623 deletions
diff --git a/NxWidgets/ChangeLog.txt b/NxWidgets/ChangeLog.txt
index 65022ea15..f932d5bc2 100644
--- a/NxWidgets/ChangeLog.txt
+++ b/NxWidgets/ChangeLog.txt
@@ -212,4 +212,3 @@
user-space work queues (someday) in order to accomplish that functionaliy.
Submitted by Petteri Aimonen.
- solutions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 103c03de3..6fad0d0ba 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -3659,6 +3659,8 @@
* configs/cloudctrl: Darcy Gong's CloudController board. This is a
small network relay development board. Based on the Shenzhou IV development
board design. It is based on the STM32F107VC MCU.
+ * arch/arm/src/stm32_serial.c and stm32_lowputc.c: Added optional RS-485
+ direction bit control. From Freddie Chopin.
* Lots of build files: ARMv7-M and MIPS32 Make.defs now include a common
Toolchain.defs file that can be used to manage toolchains in a more
configurable way. Contributed by Mike Smith
@@ -3666,4 +3668,10 @@
Mike's Toolchain.defs.
* tools/configure.sh: Adapted to handle paths and setenv.bat files correctly
for native Windows builds.
-
+ * More of build files: AVR and AVR32 Make.defs now include a common
+ Toolchain.defs file that can be used to manage toolchains in a more
+ configurable way. Contributed by Mike Smith
+ * tools/incdir.sh and incdir.bat: Add -s option to generate system header
+ file paths.
+ * nuttx/arch/arm/src/arm/Toolchain.defs: Add support for more ARM toolchains
+ (from Mike Smith).
diff --git a/nuttx/arch/arm/Kconfig b/nuttx/arch/arm/Kconfig
index eb3bfe85b..3233918ca 100644
--- a/nuttx/arch/arm/Kconfig
+++ b/nuttx/arch/arm/Kconfig
@@ -256,6 +256,9 @@ config DEBUG_HARDFAULT
if ARCH_CORTEXM3 || ARCH_CORTEXM4
source arch/arm/src/armv7-m/Kconfig
endif
+if ARCH_ARM7TDMI || ARCH_ARM926EJS
+source arch/arm/src/arm/Kconfig
+endif
if ARCH_CHIP_C5471
source arch/arm/src/c5471/Kconfig
endif
diff --git a/nuttx/arch/arm/src/arm/Kconfig b/nuttx/arch/arm/src/arm/Kconfig
new file mode 100644
index 000000000..0d08d89a8
--- /dev/null
+++ b/nuttx/arch/arm/src/arm/Kconfig
@@ -0,0 +1,35 @@
+#
+# For a description of the syntax of this configuration file,
+# see misc/tools/kconfig-language.txt.
+#
+
+comment "ARM Configuration Options"
+
+choice
+ prompt "Toolchain Selection"
+ default ARM_TOOLCHAIN_CODESOURCERYW if HOST_WINDOWS
+ default ARM_TOOLCHAIN_GNU_EABI if !HOST_WINDOWS
+
+config ARM_TOOLCHAIN_BUILDROOT
+ bool "Buildroot (Cygwin or Linux)"
+ depends on !WINDOWS_NATIVE
+
+config ARM_TOOLCHAIN_CODESOURCERYL
+ bool "CodeSourcery GNU toolchain under Linux"
+ depends on HOST_LINUX
+
+config ARM_TOOLCHAIN_CODESOURCERYW
+ bool "CodeSourcery GNU toolchain under Windows"
+ depends on HOST_WINDOWS
+
+config ARM_TOOLCHAIN_DEVKITARM
+ bool "devkitARM GNU toolchain"
+ depends on HOST_WINDOWS
+
+config ARM_TOOLCHAIN_GNU_EABI
+ bool "Generic GNU EABI toolchain"
+ ---help---
+ This option should work for any modern GNU toolchain (GCC 4.5 or newer)
+ configured for arm-none-eabi.
+
+endchoice
diff --git a/nuttx/arch/arm/src/arm/Toolchain.defs b/nuttx/arch/arm/src/arm/Toolchain.defs
new file mode 100644
index 000000000..defe30b51
--- /dev/null
+++ b/nuttx/arch/arm/src/arm/Toolchain.defs
@@ -0,0 +1,146 @@
+############################################################################
+# arch/arm/src/armv/Toolchain.defs
+#
+# Copyright (C) 2012 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.
+#
+############################################################################
+
+# Setup for the selected toolchain
+
+#
+# Handle old-style chip-specific toolchain names in the absence of
+# a new-style toolchain specification, force the selection of a single
+# toolchain and allow the selected toolchain to be overridden by a
+# command-line selection.
+#
+
+ifeq ($(filter y, \
+ $(CONFIG_DM320_BUILDROOT) \
+ $(CONFIG_LPC313X_BUILDROOT) \
+ $(CONFIG_LPC31_BUILDROOT) \
+ $(CONFIG_OLIMEX_LPC2378_BUILDROOT) \
+ $(CONFIG_ARM_TOOLCHAIN_BUILDROOT) \
+ ),y)
+ CONFIG_ARM_TOOLCHAIN ?= BUILDROOT
+endif
+ifeq ($(filter y, \
+ $(CONFIG_DM320_CODESOURCERYL) \
+ $(CONFIG_LPC31_CODESOURCERYL) \
+ $(CONFIG_OLIMEX_LPC2378_CODESOURCERYL) \
+ $(CONFIG_ARM_TOOLCHAIN_CODESOURCERYL) \
+ ),y)
+ CONFIG_ARM_TOOLCHAIN ?= CODESOURCERYL
+endif
+ifeq ($(filter y, \
+ $(CONFIG_DM320_CODESOURCERYW) \
+ $(CONFIG_LPC31_CODESOURCERYW) \
+ $(CONFIG_OLIMEX_LPC2378_CODESOURCERYW) \
+ $(CONFIG_ARM_TOOLCHAIN_CODESOURCERYW) \
+ ),y)
+ CONFIG_ARM_TOOLCHAIN ?= CODESOURCERYW
+endif
+ifeq ($(filter y, \
+ $(CONFIG_DM320_DEVKITARM) \
+ $(CONFIG_LPC31_DEVKITARM) \
+ $(CONFIG_OLIMEX_LPC2378_DEVKITARM) \
+ $(CONFIG_ARM_TOOLCHAIN_DEVKITARM) \
+ ),y)
+ CONFIG_ARM_TOOLCHAIN ?= DEVKITARM
+endif
+ifeq ($(filter y, \
+ $(CONFIG_ARM_TOOLCHAIN_GNU_EABI) \
+ ),y)
+ CONFIG_ARM_TOOLCHAIN ?= GNU_EABI
+endif
+
+#
+# Supported toolchains
+#
+# TODO - It's likely that all of these toolchains now support the
+# CortexM4. Since they are all GCC-based, we could almost
+# certainly simplify this further.
+#
+# Each toolchain definition should set:
+#
+# CROSSDEV The GNU toolchain triple (command prefix)
+# ARCROSSDEV If required, an alternative prefix used when
+# invoking ar and nm.
+# ARCHCPUFLAGS CPU-specific flags selecting the instruction set
+# FPU options, etc.
+# MAXOPTIMIZATION The maximum optimization level that results in
+# reliable code generation.
+#
+
+# NuttX buildroot under Linux or Cygwin
+
+ifeq ($(CONFIG_ARM_TOOLCHAIN),BUILDROOT)
+ CROSSDEV = arm-nuttx-elf-
+ ARCROSSDEV = arm-nuttx-elf-
+ MAXOPTIMIZATION = -Os
+endif
+
+# CodeSourcery under Linux
+
+ifeq ($(CONFIG_ARM_TOOLCHAIN),CODESOURCERYL)
+ CROSSDEV = arm-none-eabi-
+ ARCROSSDEV = arm-none-eabi-
+ MAXOPTIMIZATION = -O2
+endif
+
+# CodeSourcery under Windows
+
+ifeq ($(CONFIG_ARM_TOOLCHAIN),CODESOURCERYW)
+ CROSSDEV = arm-none-eabi-
+ ARCROSSDEV = arm-none-eabi-
+ MAXOPTIMIZATION = -O2
+ ifneq ($(CONFIG_WINDOWS_NATIVE),y)
+ WINTOOL = y
+ endif
+endif
+
+# devkitARM under Windows
+
+ifeq ($(CONFIG_ARM_TOOLCHAIN),DEVKITARM)
+ CROSSDEV = arm-eabi-
+ ARCROSSDEV = arm-eabi-
+ ifneq ($(CONFIG_WINDOWS_NATIVE),y)
+ WINTOOL = y
+ endif
+endif
+
+# Generic GNU EABI toolchain on OS X, Linux or any typical Posix system
+
+ifeq ($(CONFIG_ARM_TOOLCHAIN),GNU_EABI)
+ CROSSDEV = arm-none-eabi-
+ ARCROSSDEV = arm-none-eabi-
+ MAXOPTIMIZATION = -O3
+endif
+
diff --git a/nuttx/arch/arm/src/armv7-m/Toolchain.defs b/nuttx/arch/arm/src/armv7-m/Toolchain.defs
index e39d7f414..e214ce8bd 100644
--- a/nuttx/arch/arm/src/armv7-m/Toolchain.defs
+++ b/nuttx/arch/arm/src/armv7-m/Toolchain.defs
@@ -143,9 +143,9 @@ endif
ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),ATOLLIC)
CROSSDEV = arm-atollic-eabi-
ARCROSSDEV = arm-atollic-eabi-
-ifneq ($(CONFIG_WINDOWS_NATIVE),y)
- WINTOOL = y
-endif
+ ifneq ($(CONFIG_WINDOWS_NATIVE),y)
+ WINTOOL = y
+ endif
ifeq ($(CONFIG_ARCH_CORTEXM4),y)
ifeq ($(CONFIG_ARCH_FPU),y)
ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard
@@ -192,9 +192,9 @@ endif
ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),CODEREDW)
CROSSDEV = arm-none-eabi-
ARCROSSDEV = arm-none-eabi-
-ifneq ($(CONFIG_WINDOWS_NATIVE),y)
- WINTOOL = y
-endif
+ ifneq ($(CONFIG_WINDOWS_NATIVE),y)
+ WINTOOL = y
+ endif
ifeq ($(CONFIG_ARCH_CORTEXM4),y)
ifeq ($(CONFIG_ARCH_FPU),y)
ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard
@@ -220,9 +220,9 @@ endif
ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),CODESOURCERYW)
CROSSDEV = arm-none-eabi-
ARCROSSDEV = arm-none-eabi-
-ifneq ($(CONFIG_WINDOWS_NATIVE),y)
- WINTOOL = y
-endif
+ ifneq ($(CONFIG_WINDOWS_NATIVE),y)
+ WINTOOL = y
+ endif
ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
endif
@@ -231,9 +231,9 @@ endif
ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),DEVKITARM)
CROSSDEV = arm-eabi-
ARCROSSDEV = arm-eabi-
-ifneq ($(CONFIG_WINDOWS_NATIVE),y)
- WINTOOL = y
-endif
+ ifneq ($(CONFIG_WINDOWS_NATIVE),y)
+ WINTOOL = y
+ endif
ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
endif
@@ -259,8 +259,8 @@ endif
ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),RAISONANCE)
CROSSDEV = arm-none-eabi-
ARCROSSDEV = arm-none-eabi-
-ifneq ($(CONFIG_WINDOWS_NATIVE),y)
- WINTOOL = y
-endif
+ ifneq ($(CONFIG_WINDOWS_NATIVE),y)
+ WINTOOL = y
+ endif
ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
endif
diff --git a/nuttx/arch/avr/Kconfig b/nuttx/arch/avr/Kconfig
index 4ebd26d5f..41b6c72d3 100644
--- a/nuttx/arch/avr/Kconfig
+++ b/nuttx/arch/avr/Kconfig
@@ -6,43 +6,6 @@
if ARCH_AVR
choice
- prompt "Toolchain"
- default AVR_BUILDROOT
-
-config AVR_WINAVR
- bool "WinAVR"
- ---help---
- For Cygwin development environment on Windows machines, you
- can use WinAVR: http://sourceforge.net/projects/winavr/files/
-
- It is assumed in some places that WinAVR is installed at
- C:/WinAVR. Edit the setenv.sh file if this is not the case.
-
- WARNING: There is an incompatible version of cygwin.dll in
- the WinAVR/bin directory! Make sure that the path to the
- correct cygwin.dll file precedes the path to the WinAVR
- binaries!
-
-config AVR_LINUXGCC
- bool "Linux GCC"
- ---help---
- For Linux, there are widely available avr-gcc packages. On
- Ubuntu, use: sudo apt-get install gcc-avr gdb-avr avr-libc
-
-config AVR_BUILDROOT
- bool "Buildroot"
- ---help---
- There is a DIY buildroot version for the AVR boards here:
- http://sourceforge.net/projects/nuttx/files/buildroot/. See
- the following section for details on building this toolchain.
-
- It is assumed in some places that buildroot toolchain is
- available at ../misc/buildroot/build_avr. Edit the setenv.sh
- file if this is not the case.
-
-endchoice
-
-choice
prompt "Atmel AVR chip selection"
default ARCH_CHIP_AT32UC3B0256
@@ -110,11 +73,16 @@ config ARCH_CHIP
default "at32uc3" if ARCH_AT32UC3
source arch/avr/src/common/Kconfig
+
+if ARCH_FAMILY_AVR
source arch/avr/src/avr/Kconfig
source arch/avr/src/at90usb/Kconfig
source arch/avr/src/atmega/Kconfig
+endif
+if ARCH_FAMILY_AVR32
source arch/avr/src/avr32/Kconfig
source arch/avr/src/at32uc3/Kconfig
+endif
config AVR_USART0
bool "USART0 specific serial device driver settings"
diff --git a/nuttx/arch/avr/src/avr/Kconfig b/nuttx/arch/avr/src/avr/Kconfig
index 99228aa2c..3c18452df 100644
--- a/nuttx/arch/avr/src/avr/Kconfig
+++ b/nuttx/arch/avr/src/avr/Kconfig
@@ -6,4 +6,57 @@
if ARCH_FAMILY_AVR
comment "AVR Configuration Options"
+choice
+ prompt "Toolchain"
+ default AVR_WINAVR if HOST_WINDOWS
+ default AVR_BUILDROOT if HOST_LINUX
+ default AVR_CROSSPACK if HOST_OSX
+
+config AVR_WINAVR
+ bool "WinAVR"
+ depends on HOST_WINDOWS
+ ---help---
+ For Cygwin development environment on Windows machines, you
+ can use WinAVR: http://sourceforge.net/projects/winavr/files/
+
+ It is assumed in some places that WinAVR is installed at
+ C:/WinAVR. Edit the setenv.sh file if this is not the case.
+
+ WARNING: There is an incompatible version of cygwin.dll in
+ the WinAVR/bin directory! Make sure that the path to the
+ correct cygwin.dll file precedes the path to the WinAVR
+ binaries!
+
+config AVR_LINUXGCC
+ bool "Linux GCC"
+ depends on HOST_LINUX
+ ---help---
+ For Linux, there are widely available avr-gcc packages. On
+ Ubuntu, use: sudo apt-get install gcc-avr gdb-avr avr-libc
+
+config AVR_CROSSPACK
+ bool "CrossPack-AVR"
+ depends on HOST_OSX
+ ---help---
+ For OS X, the AVR CrossPack toolchain is supported:
+ http://www.obdev.at/products/crosspack/index.html
+
+ It is assumed that /usr/local/CrossPack-AVR/bin is on the
+ user's path. Edit the setenv.sh file if this is not the
+ case.
+
+config AVR_BUILDROOT
+ bool "Buildroot"
+ depends on HOST_LINUX || HOST_WINDOWS
+ ---help---
+ There is a DIY buildroot version for the AVR boards here:
+ http://sourceforge.net/projects/nuttx/files/buildroot/. See
+ the following section for details on building this toolchain.
+
+ It is assumed in some places that buildroot toolchain is
+ available at ../misc/buildroot/build_avr. Edit the setenv.sh
+ file if this is not the case.
+
+endchoice
+
endif
diff --git a/nuttx/arch/avr/src/avr/Toolchain.defs b/nuttx/arch/avr/src/avr/Toolchain.defs
new file mode 100644
index 000000000..96eb273f6
--- /dev/null
+++ b/nuttx/arch/avr/src/avr/Toolchain.defs
@@ -0,0 +1,117 @@
+############################################################################
+# arch/avr/src/avr/Toolchain.defs
+#
+# Copyright (C) 2012 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.
+#
+############################################################################
+
+# Setup for the selected toolchain
+
+#
+# Handle old-style chip-specific toolchain names in the absence of
+# a new-style toolchain specification, force the selection of a single
+# toolchain and allow the selected toolchain to be overridden by a
+# command-line selection.
+#
+
+ifeq ($(filter y, \
+ $(CONFIG_AVR_BUILDROOT) \
+ ),y)
+ CONFIG_AVR_TOOLCHAIN ?= BUILDROOT
+endif
+ifeq ($(filter y, \
+ $(CONFIG_AVR_CROSSPACK) \
+ ),y)
+ CONFIG_AVR_TOOLCHAIN ?= CROSSPACK
+endif
+ifeq ($(filter y, \
+ $(CONFIG_AVR_LINUXGCC) \
+ ),y)
+ CONFIG_AVR_TOOLCHAIN ?= LINUXGCC
+endif
+ifeq ($(filter y, \
+ $(CONFIG_AVR_WINAVR) \
+ ),y)
+ CONFIG_AVR_TOOLCHAIN ?= WINAVR
+endif
+
+# Chip-specific CPU flags
+
+ifeq ($(CONFIG_ARCH_CHIP_ATMEGA128),y)
+ ARCHCPUFLAGS += -mmcu=atmega128
+else ifeq ($(CONFIG_ARCH_CHIP_AT90USB646),y)
+ ARCHCPUFLAGS += -mmcu=at90usb646
+else ifeq ($(CONFIG_ARCH_CHIP_AT90USB647),y)
+ ARCHCPUFLAGS += -mmcu=at90usb647
+else ifeq ($(CONFIG_ARCH_CHIP_AT90USB1286),y)
+ ARCHCPUFLAGS += -mmcu=at90usb1286
+else ifeq ($(CONFIG_ARCH_CHIP_AT90USB1287),y)
+ ARCHCPUFLAGS += -mmcu=at90usb1287
+else
+ $(error "No valid CONFIG_ARCH_CHIP_ set in the configuration")
+endif
+
+# NuttX buildroot GCC toolchain under Linux or Cygwin
+
+ifeq ($(CONFIG_AVR_TOOLCHAIN),BUILDROOT)
+ CROSSDEV = avr-nuttx-elf-
+ MAXOPTIMIZATION = -O2
+ LDFLAGS += -nostartfiles -nodefaultlibs
+endif
+
+# AVR CrossPack under OS X
+
+ifeq ($(CONFIG_AVR_TOOLCHAIN),CROSSPACK)
+ CROSSDEV = avr-
+ MAXOPTIMIZATION = -O2
+ LDFLAGS += -nostartfiles -nodefaultlibs
+endif
+
+# GCC toolchain under Linux
+
+ifeq ($(CONFIG_AVR_TOOLCHAIN),LINUXGCC)
+ CROSSDEV = avr-
+ MAXOPTIMIZATION = -O2
+ LDFLAGS += -nostartfiles -nodefaultlibs
+endif
+
+# WinAVR toolchain under Windows/Cygwin
+
+ifeq ($(CONFIG_AVR_TOOLCHAIN),WINAVR)
+ CROSSDEV = avr-
+ ifneq ($(CONFIG_WINDOWS_NATIVE),y)
+ WINTOOL = y
+ endif
+ MAXOPTIMIZATION = -O2
+ LDFLAGS += -nostartfiles -nodefaultlibs
+endif
+
+
diff --git a/nuttx/arch/avr/src/avr32/Kconfig b/nuttx/arch/avr/src/avr32/Kconfig
index 12cc033cb..2e604cade 100644
--- a/nuttx/arch/avr/src/avr32/Kconfig
+++ b/nuttx/arch/avr/src/avr32/Kconfig
@@ -6,4 +6,7 @@
if ARCH_FAMILY_AVR32
comment "AVR32 Configuration Options"
+# Note - no toolchain selection here as there is only one
+# supported toolchain.
+
endif
diff --git a/nuttx/arch/avr/src/avr32/Toolchain.defs b/nuttx/arch/avr/src/avr32/Toolchain.defs
new file mode 100644
index 000000000..6a4b1234e
--- /dev/null
+++ b/nuttx/arch/avr/src/avr32/Toolchain.defs
@@ -0,0 +1,63 @@
+############################################################################
+# arch/avr/src/avr32/Toolchain.defs
+#
+# Copyright (C) 2012 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.
+#
+############################################################################
+
+# Setup for the selected toolchain
+
+#
+# Since all of the supported toolchains are variants of the Atmel-patched
+# GCC, the only interesting question to answer here is whether or not
+# the build is hosted on Windows, and how to override the configuration.
+#
+
+CROSSDEV = avr32-
+ARCHCPUFLAGS = -mpart=uc3b0256
+
+ifeq ($(filter y, \
+ $(CONFIG_AVR32_AVRTOOLSW) \
+ $(CONFIG_HOST_WINDOWS) \
+ ),y)
+ # AVR Tools under Windows
+ CONFIG_AVR32_TOOLCHAIN ?= AVRTOOLSW
+else
+ CONFIG_AVR32_TOOLCHAIN ?= GNU
+endif
+
+ifeq ($(CONFIG_AVR32_TOOLCHAIN),AVRTOOLSW)
+ ifneq ($(CONFIG_WINDOWS_NATIVE),y)
+ WINTOOL = y
+ endif
+else
+ # AVR Tools or avr32-toolchain from https://github.com/jsnyder/avr32-toolchain
+endif
diff --git a/nuttx/arch/mips/src/mips32/Toolchain.defs b/nuttx/arch/mips/src/mips32/Toolchain.defs
index 554e5f044..bd509b86c 100644
--- a/nuttx/arch/mips/src/mips32/Toolchain.defs
+++ b/nuttx/arch/mips/src/mips32/Toolchain.defs
@@ -42,6 +42,8 @@
# command-line selection.
#
ifeq ($(filter y, \
+ $(CONFIG_PIC32MX_PINGUINOL) \
+ $(CONFIG_MIPS32_TOOLCHAIN_PINGUINOL) \
$(CONFIG_MIPS32_TOOLCHAIN_GNU_ELF) \
),y)
CONFIG_MIPS32_TOOLCHAIN ?= GNU_ELF
@@ -82,12 +84,6 @@ ifeq ($(filter y, \
),y)
CONFIG_MIPS32_TOOLCHAIN ?= PINGUINOW
endif
-ifeq ($(filter y, \
- $(CONFIG_PIC32MX_PINGUINOL) \
- $(CONFIG_MIPS32_TOOLCHAIN_PINGUINOL) \
- ),y)
- CONFIG_MIPS32_TOOLCHAIN ?= PINGUINOL
-endif
#
# Supported toolchains
@@ -104,6 +100,7 @@ endif
#
# Generic GNU mip32 toolchain on OS X or Linux
+# including Pinguino mips-elf toolchain
ifeq ($(CONFIG_MIPS32_TOOLCHAIN),GNU_ELF)
CROSSDEV = mips-elf-
@@ -131,9 +128,9 @@ endif
ifeq ($(CONFIG_MIPS32_TOOLCHAIN),MICROCHIPW)
CROSSDEV = pic32-
# CROSSDEV = xc32-
-ifneq ($(CONFIG_WINDOWS_NATIVE),y)
- WINTOOL = y
-endif
+ ifneq ($(CONFIG_WINDOWS_NATIVE),y)
+ WINTOOL = y
+ endif
MAXOPTIMIZATION = -O2
ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data
ARCHPICFLAGS = -fpic -membedded-pic
@@ -158,9 +155,9 @@ endif
ifeq ($(CONFIG_MIPS32_TOOLCHAIN),MICROCHIPW_LITE)
CROSSDEV = pic32-
# CROSSDEV = xc32-
-ifneq ($(CONFIG_WINDOWS_NATIVE),y)
- WINTOOL = y
-endif
+ ifneq ($(CONFIG_WINDOWS_NATIVE),y)
+ WINTOOL = y
+ endif
# MAXOPTIMIZATION = -O2
ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data
ARCHPICFLAGS = -fpic -membedded-pic
@@ -183,20 +180,9 @@ endif
ifeq ($(CONFIG_MIPS32_TOOLCHAIN),PINGUINOW)
CROSSDEV = mips-
-ifneq ($(CONFIG_WINDOWS_NATIVE),y)
- WINTOOL = y
-endif
- MAXOPTIMIZATION = -O2
- ARCHCPUFLAGS = -mlong32 -membedded-data -msoft-float -march=24kc -EL
- ARCHPICFLAGS = -fpic -membedded-pic
- LDFLAGS += -nostartfiles -nodefaultlibs
- LDSCRIPT = mips-elf-debug.ld
-endif
-
-# Pinguino mips-elf toolchain under OS X or Linux
-
-ifeq ($(CONFIG_MIPS32_TOOLCHAIN),PINGUINOL)
- CROSSDEV = mips-elf-
+ ifneq ($(CONFIG_WINDOWS_NATIVE),y)
+ WINTOOL = y
+ endif
MAXOPTIMIZATION = -O2
ARCHCPUFLAGS = -mlong32 -membedded-data -msoft-float -march=24kc -EL
ARCHPICFLAGS = -fpic -membedded-pic
diff --git a/nuttx/configs/amber/README.txt b/nuttx/configs/amber/README.txt
index 63fa5d41f..56e31ba7f 100644
--- a/nuttx/configs/amber/README.txt
+++ b/nuttx/configs/amber/README.txt
@@ -187,6 +187,12 @@ Atmel AVRISP mkII Connection
Toolchains
^^^^^^^^^^
+The toolchain may be selected using the mconf tool (via 'make menuconfig'),
+by editing the existing configuration file (defconfig), or by overriding
+the toolchain on the make commandline with CONFIG_AVR_TOOLCHAIN=<toolchain>.
+
+The valid values for <toolchain> are BUILDROOT, CROSSPACK, LINUXGCC and WINAVR.
+
Buildroot:
There is a DIY buildroot version for the AVR boards here:
@@ -223,6 +229,14 @@ Linux:
After configuring NuttX, make sure that CONFIG_AVR_LINUXGCC=y is set in your
.config file.
+Mac OS X:
+
+ For Mac OS X, the CrossPack for AVR toolchain is available from:
+
+ http://www.obdev.at/products/crosspack/index.html
+
+ This toolchain is functionally equivalent to the Linux GCC toolchain.
+
Windows Native Toolchains
^^^^^^^^^^^^^^^^^^^^^^^^^
diff --git a/nuttx/configs/amber/hello/Make.defs b/nuttx/configs/amber/hello/Make.defs
index 15c31f192..e7f998dc7 100644
--- a/nuttx/configs/amber/hello/Make.defs
+++ b/nuttx/configs/amber/hello/Make.defs
@@ -35,33 +35,7 @@
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
-
-# Setup for the selected toolchain
-
-ifeq ($(CONFIG_AVR_WINAVR),y)
- # WinAVR toolchain under Windows/Cygwin
- CROSSDEV = avr-
- WINTOOL = y
- MAXOPTIMIZATION = -O2
- ARCHCPUFLAGS = -mmcu=atmega128
- LDFLAGS += -nostartfiles -nodefaultlibs
-endif
-
-ifeq ($(CONFIG_AVR_LINUXGCC),y)
- # GCC toolchain under Linux
- CROSSDEV = avr-
- MAXOPTIMIZATION = -O2
- ARCHCPUFLAGS = -mmcu=atmega128
- LDFLAGS += -nostartfiles -nodefaultlibs
-endif
-
-ifeq ($(CONFIG_AVR_BUILDROOT),y)
- # NuttX buildroot GCC toolchain under Linux or Cygwin
- CROSSDEV = avr-nuttx-elf-
- MAXOPTIMIZATION = -O2
- ARCHCPUFLAGS = -mmcu=atmega128
- LDFLAGS += -nostartfiles -nodefaultlibs
-endif
+include ${TOPDIR}/arch/avr/src/avr/Toolchain.defs
ifeq ($(WINTOOL),y)
# Windows-native toolchains
diff --git a/nuttx/configs/avr32dev1/README.txt b/nuttx/configs/avr32dev1/README.txt
index 68d019227..37e15dc9b 100644
--- a/nuttx/configs/avr32dev1/README.txt
+++ b/nuttx/configs/avr32dev1/README.txt
@@ -112,7 +112,7 @@ PA17 and PA23 are avaiable from the AVR32DEV1:
Development Environment
^^^^^^^^^^^^^^^^^^^^^^^
- Either Linux or Cygwin on Windows can be used for the development environment.
+ Linux, Mac OS X or Cygwin on Windows can be used for the development environment.
The source has been built only using the GNU toolchain (see below). Other
toolchains will likely cause problems. Testing was performed using the Cygwin
environment.
@@ -140,6 +140,16 @@ WinAVR:
AVR32 toolchain as well as the AVR toolchain and various support
libraries and header files.
+AVR32 Toolchain Builder:
+
+ A third option is to build the toolchain yourself. For OS X and Linux systems,
+ this Makefile will build a complete gcc-4.4.3 toolchain:
+
+ https://github.com/jsnyder/avr32-toolchain
+
+ By default the toolchain installs into ${HOME}/avr-32-tools-<somedate> and
+ the bin subdirectory must be added to your path before compiling.
+
IDEs
^^^^
diff --git a/nuttx/configs/avr32dev1/nsh/Make.defs b/nuttx/configs/avr32dev1/nsh/Make.defs
index aa84884d0..bccb35069 100644
--- a/nuttx/configs/avr32dev1/nsh/Make.defs
+++ b/nuttx/configs/avr32dev1/nsh/Make.defs
@@ -35,20 +35,7 @@
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
-
-# Setup for the selected toolchain
-
-ifeq ($(CONFIG_AVR32_AVRTOOLSW),y)
- # AVR Tools under Windows
- CROSSDEV = avr32-
- WINTOOL = y
- ARCHCPUFLAGS = -mpart=uc3b0256
-endif
-ifeq ($(CONFIG_AVR32_AVRTOOLSL),y)
- # AVR Tools under Linux
- CROSSDEV = avr32-
- ARCHCPUFLAGS = -mpart=uc3b0256
-endif
+include ${TOPDIR}/arch/avr/src/avr32/Toolchain.defs
ifeq ($(WINTOOL),y)
# Windows-native toolchains
diff --git a/nuttx/configs/ea3131/README.txt b/nuttx/configs/ea3131/README.txt
index 2912bf318..fcfc0792f 100644
--- a/nuttx/configs/ea3131/README.txt
+++ b/nuttx/configs/ea3131/README.txt
@@ -34,8 +34,9 @@ GNU Toolchain Options
1. The CodeSourcery GNU toolchain,
2. The devkitARM GNU toolchain,
- 3. Raisonance GNU toolchain, or
- 4. The NuttX buildroot Toolchain (see below).
+ 3. Raisonance GNU toolchain,
+ 4. The NuttX buildroot Toolchain (see below), or
+ 5. Any generic arm-none-eabi GNU toolchain.
All testing has been conducted using the NuttX buildroot toolchain. However,
the make system is setup to default to use the devkitARM toolchain. To use
@@ -47,10 +48,16 @@ GNU Toolchain Options
CONFIG_LPC31_CODESOURCERYL=y : CodeSourcery under Linux
CONFIG_LPC31_DEVKITARM=y : devkitARM under Windows
CONFIG_LPC31_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default)
+ CONFIG_ARM_TOOLCHAIN_GNU_EABI : Generic arm-none-eabi toolchain
If you are not using CONFIG_LPC31_BUILDROOT, then you may also have to modify
the PATH in the setenv.h file if your make cannot find the tools.
+ The toolchain may also be set using the mconf utility (make menuconfig) or by
+ passing CONFIG_ARM_TOOLCHAIN=<toolchain> to make, where <toolchain> is one
+ of CODESOURCERYW, CODESOURCERYL, DEVKITARM, BUILDROOT or GNU_EABI as described
+ above.
+
NOTE: the CodeSourcery (for Windows), devkitARM, and Raisonance toolchains are
Windows native toolchains. The CodeSourcey (for Linux) and NuttX buildroot
toolchains are Cygwin and/or Linux native toolchains. There are several limitations
@@ -87,6 +94,23 @@ GNU Toolchain Options
the paths to Cygwin's /bin and /usr/bin directories appear BEFORE the devkitARM
path or will get the wrong version of make.
+ Generic arm-none-eabi GNU Toolchain
+ -----------------------------------
+ There are a number of toolchain projects providing support for ARMv4/v5
+ class processors, including:
+
+ GCC ARM Embedded
+ https://launchpad.net/gcc-arm-embedded
+
+ Summon ARM Toolchain
+ https://github.com/esden/summon-arm-toolchain
+
+ Yagarto
+ http://www.yagarto.de
+
+ Others exist for various Linux distributions, MacPorts, etc. Any version
+ based on GCC 4.6.3 or later should work.
+
IDEs
^^^^
diff --git a/nuttx/configs/ea3131/nsh/Make.defs b/nuttx/configs/ea3131/nsh/Make.defs
index a061eb22c..1bfd6f4d5 100644
--- a/nuttx/configs/ea3131/nsh/Make.defs
+++ b/nuttx/configs/ea3131/nsh/Make.defs
@@ -35,30 +35,7 @@
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
-
-# Setup for the selected toolchain
-
-ifeq ($(CONFIG_LPC31_CODESOURCERYW),y)
- # CodeSourcery under Windows
- CROSSDEV = arm-none-eabi-
- WINTOOL = y
- MAXOPTIMIZATION = -O2
-endif
-ifeq ($(CONFIG_LPC31_CODESOURCERYL),y)
- # CodeSourcery under Linux
- CROSSDEV = arm-none-eabi-
- MAXOPTIMIZATION = -O2
-endif
-ifeq ($(CONFIG_LPC31_DEVKITARM),y)
- # devkitARM under Windows
- CROSSDEV = arm-eabi-
- WINTOOL = y
-endif
-ifeq ($(CONFIG_LPC31_BUILDROOT),y)
- # NuttX buildroot under Linux or Cygwin
- CROSSDEV = arm-nuttx-elf-
- MAXOPTIMIZATION = -Os
-endif
+include ${TOPDIR}/arch/arm/src/arm/Toolchain.defs
ifeq ($(WINTOOL),y)
# Windows-native toolchains
diff --git a/nuttx/configs/ea3131/ostest/Make.defs b/nuttx/configs/ea3131/ostest/Make.defs
index ba750e212..9c8780a4a 100644
--- a/nuttx/configs/ea3131/ostest/Make.defs
+++ b/nuttx/configs/ea3131/ostest/Make.defs
@@ -35,30 +35,7 @@
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
-
-# Setup for the selected toolchain
-
-ifeq ($(CONFIG_LPC31_CODESOURCERYW),y)
- # CodeSourcery under Windows
- CROSSDEV = arm-none-eabi-
- WINTOOL = y
- MAXOPTIMIZATION = -O2
-endif
-ifeq ($(CONFIG_LPC31_CODESOURCERYL),y)
- # CodeSourcery under Linux
- CROSSDEV = arm-none-eabi-
- MAXOPTIMIZATION = -O2
-endif
-ifeq ($(CONFIG_LPC31_DEVKITARM),y)
- # devkitARM under Windows
- CROSSDEV = arm-eabi-
- WINTOOL = y
-endif
-ifeq ($(CONFIG_LPC31_BUILDROOT),y)
- # NuttX buildroot under Linux or Cygwin
- CROSSDEV = arm-nuttx-elf-
- MAXOPTIMIZATION = -Os
-endif
+include ${TOPDIR}/arch/arm/src/arm/Toolchain.defs
ifeq ($(WINTOOL),y)
# Windows-native toolchains
diff --git a/nuttx/configs/ea3131/pgnsh/Make.defs b/nuttx/configs/ea3131/pgnsh/Make.defs
index c142319de..f71a0920e 100644
--- a/nuttx/configs/ea3131/pgnsh/Make.defs
+++ b/nuttx/configs/ea3131/pgnsh/Make.defs
@@ -35,30 +35,7 @@
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
-
-# Setup for the selected toolchain
-
-ifeq ($(CONFIG_LPC31_CODESOURCERYW),y)
- # CodeSourcery under Windows
- CROSSDEV = arm-none-eabi-
- WINTOOL = y
- MAXOPTIMIZATION = -O2
-endif
-ifeq ($(CONFIG_LPC31_CODESOURCERYL),y)
- # CodeSourcery under Linux
- CROSSDEV = arm-none-eabi-
- MAXOPTIMIZATION = -O2
-endif
-ifeq ($(CONFIG_LPC31_DEVKITARM),y)
- # devkitARM under Windows
- CROSSDEV = arm-eabi-
- WINTOOL = y
-endif
-ifeq ($(CONFIG_LPC31_BUILDROOT),y)
- # NuttX buildroot under Linux or Cygwin
- CROSSDEV = arm-nuttx-elf-
- MAXOPTIMIZATION = -Os
-endif
+include ${TOPDIR}/arch/arm/src/arm/Toolchain.defs
ifeq ($(WINTOOL),y)
# Windows-native toolchains
diff --git a/nuttx/configs/ea3131/usbserial/Make.defs b/nuttx/configs/ea3131/usbserial/Make.defs
index ef64e2615..1b1eb45d5 100644
--- a/nuttx/configs/ea3131/usbserial/Make.defs
+++ b/nuttx/configs/ea3131/usbserial/Make.defs
@@ -35,30 +35,7 @@
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
-
-# Setup for the selected toolchain
-
-ifeq ($(CONFIG_LPC31_CODESOURCERYW),y)
- # CodeSourcery under Windows
- CROSSDEV = arm-none-eabi-
- WINTOOL = y
- MAXOPTIMIZATION = -O2
-endif
-ifeq ($(CONFIG_LPC31_CODESOURCERYL),y)
- # CodeSourcery under Linux
- CROSSDEV = arm-none-eabi-
- MAXOPTIMIZATION = -O2
-endif
-ifeq ($(CONFIG_LPC31_DEVKITARM),y)
- # devkitARM under Windows
- CROSSDEV = arm-eabi-
- WINTOOL = y
-endif
-ifeq ($(CONFIG_LPC31_BUILDROOT),y)
- # NuttX buildroot under Linux or Cygwin
- CROSSDEV = arm-nuttx-elf-
- MAXOPTIMIZATION = -Os
-endif
+include ${TOPDIR}/arch/arm/src/arm/Toolchain.defs
ifeq ($(WINTOOL),y)
# Windows-native toolchains
diff --git a/nuttx/configs/ea3131/usbstorage/Make.defs b/nuttx/configs/ea3131/usbstorage/Make.defs
index 739360615..7155ccf5c 100644
--- a/nuttx/configs/ea3131/usbstorage/Make.defs
+++ b/nuttx/configs/ea3131/usbstorage/Make.defs
@@ -35,30 +35,7 @@
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
-
-# Setup for the selected toolchain
-
-ifeq ($(CONFIG_LPC31_CODESOURCERYW),y)
- # CodeSourcery under Windows
- CROSSDEV = arm-none-eabi-
- WINTOOL = y
- MAXOPTIMIZATION = -O2
-endif
-ifeq ($(CONFIG_LPC31_CODESOURCERYL),y)
- # CodeSourcery under Linux
- CROSSDEV = arm-none-eabi-
- MAXOPTIMIZATION = -O2
-endif
-ifeq ($(CONFIG_LPC31_DEVKITARM),y)
- # devkitARM under Windows
- CROSSDEV = arm-eabi-
- WINTOOL = y
-endif
-ifeq ($(CONFIG_LPC31_BUILDROOT),y)
- # NuttX buildroot under Linux or Cygwin
- CROSSDEV = arm-nuttx-elf-
- MAXOPTIMIZATION = -Os
-endif
+include ${TOPDIR}/arch/arm/src/arm/Toolchain.defs
ifeq ($(WINTOOL),y)
# Windows-native toolchains
diff --git a/nuttx/configs/ea3152/README.txt b/nuttx/configs/ea3152/README.txt
index 7aa57e3ae..da57945bd 100644
--- a/nuttx/configs/ea3152/README.txt
+++ b/nuttx/configs/ea3152/README.txt
@@ -33,8 +33,9 @@ GNU Toolchain Options
1. The CodeSourcery GNU toolchain,
2. The devkitARM GNU toolchain,
- 3. Raisonance GNU toolchain, or
- 4. The NuttX buildroot Toolchain (see below).
+ 3. Raisonance GNU toolchain,
+ 4. The NuttX buildroot Toolchain (see below), or
+ 5. Any generic arm-none-eabi GNU toolchain.
All testing has been conducted using the NuttX buildroot toolchain. However,
the make system is setup to default to use the devkitARM toolchain. To use
@@ -46,10 +47,16 @@ GNU Toolchain Options
CONFIG_LPC31_CODESOURCERYL=y : CodeSourcery under Linux
CONFIG_LPC31_DEVKITARM=y : devkitARM under Windows
CONFIG_LPC31_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default)
+ CONFIG_ARM_TOOLCHAIN_GNU_EABI : Generic arm-none-eabi toolchain
If you are not using CONFIG_LPC31_BUILDROOT, then you may also have to modify
the PATH in the setenv.h file if your make cannot find the tools.
+ The toolchain may also be set using the mconf utility (make menuconfig) or by
+ passing CONFIG_ARM_TOOLCHAIN=<toolchain> to make, where <toolchain> is one
+ of CODESOURCERYW, CODESOURCERYL, DEVKITARM, BUILDROOT or GNU_EABI as described
+ above.
+
NOTE: the CodeSourcery (for Windows), devkitARM, and Raisonance toolchains are
Windows native toolchains. The CodeSourcey (for Linux) and NuttX buildroot
toolchains are Cygwin and/or Linux native toolchains. There are several limitations
@@ -85,6 +92,23 @@ GNU Toolchain Options
NOTE 2: The devkitARM toolchain includes a version of MSYS make. Make sure that
the paths to Cygwin's /bin and /usr/bin directories appear BEFORE the devkitARM
path or will get the wrong version of make.
+
+ Generic arm-none-eabi GNU Toolchain
+ -----------------------------------
+ There are a number of toolchain projects providing support for ARMv4/v5
+ class processors, including:
+
+ GCC ARM Embedded
+ https://launchpad.net/gcc-arm-embedded
+
+ Summon ARM Toolchain
+ https://github.com/esden/summon-arm-toolchain
+
+ Yagarto
+ http://www.yagarto.de
+
+ Others exist for various Linux distributions, MacPorts, etc. Any version
+ based on GCC 4.6.3 or later should work.
IDEs
^^^^
diff --git a/nuttx/configs/ea3152/ostest/Make.defs b/nuttx/configs/ea3152/ostest/Make.defs
index f69eb5e95..45168938a 100644
--- a/nuttx/configs/ea3152/ostest/Make.defs
+++ b/nuttx/configs/ea3152/ostest/Make.defs
@@ -35,30 +35,7 @@
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
-
-# Setup for the selected toolchain
-
-ifeq ($(CONFIG_LPC31_CODESOURCERYW),y)
- # CodeSourcery under Windows
- CROSSDEV = arm-none-eabi-
- WINTOOL = y
- MAXOPTIMIZATION = -O2
-endif
-ifeq ($(CONFIG_LPC31_CODESOURCERYL),y)
- # CodeSourcery under Linux
- CROSSDEV = arm-none-eabi-
- MAXOPTIMIZATION = -O2
-endif
-ifeq ($(CONFIG_LPC31_DEVKITARM),y)
- # devkitARM under Windows
- CROSSDEV = arm-eabi-
- WINTOOL = y
-endif
-ifeq ($(CONFIG_LPC31_BUILDROOT),y)
- # NuttX buildroot under Linux or Cygwin
- CROSSDEV = arm-nuttx-elf-
- MAXOPTIMIZATION = -Os
-endif
+include ${TOPDIR}/arch/arm/src/arm/Toolchain.defs
ifeq ($(WINTOOL),y)
# Windows-native toolchains
diff --git a/nuttx/configs/micropendous3/README.txt b/nuttx/configs/micropendous3/README.txt
index 583f1d8d8..1b0f2c8ce 100644
--- a/nuttx/configs/micropendous3/README.txt
+++ b/nuttx/configs/micropendous3/README.txt
@@ -198,7 +198,13 @@ Toolchains
There are several toolchain options. However, testing has been performed
using *only* the NuttX buildroot toolchain described below. Therefore,
-the NuttX buildroot toolchain is the recommended choice:
+the NuttX buildroot toolchain is the recommended choice.
+
+The toolchain may be selected using the mconf tool (via 'make menuconfig'),
+by editing the existing configuration file (defconfig), or by overriding
+the toolchain on the make commandline with CONFIG_AVR_TOOLCHAIN=<toolchain>.
+
+The valid values for <toolchain> are BUILDROOT, CROSSPACK, LINUXGCC and WINAVR.
Buildroot:
@@ -236,6 +242,14 @@ Linux:
After configuring NuttX, make sure that CONFIG_AVR_LINUXGCC=y is set in your
.config file.
+Mac OS X:
+
+ For Mac OS X, the CrossPack for AVR toolchain is available from:
+
+ http://www.obdev.at/products/crosspack/index.html
+
+ This toolchain is functionally equivalent to the Linux GCC toolchain.
+
Windows Native Toolchains
^^^^^^^^^^^^^^^^^^^^^^^^^
diff --git a/nuttx/configs/micropendous3/hello/Make.defs b/nuttx/configs/micropendous3/hello/Make.defs
index 69073bb43..a40098fff 100644
--- a/nuttx/configs/micropendous3/hello/Make.defs
+++ b/nuttx/configs/micropendous3/hello/Make.defs
@@ -35,33 +35,7 @@
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
-
-# Setup for the selected toolchain
-
-ifeq ($(CONFIG_AVR_WINAVR),y)
- # WinAVR toolchain under Windows/Cygwin
- CROSSDEV = avr-
- WINTOOL = y
- MAXOPTIMIZATION = -O2
- ARCHCPUFLAGS = -mmcu=at90usb647
- LDFLAGS += -nostartfiles -nodefaultlibs
-endif
-
-ifeq ($(CONFIG_AVR_LINUXGCC),y)
- # GCC toolchain under Linux
- CROSSDEV = avr-
- MAXOPTIMIZATION = -O2
- ARCHCPUFLAGS = -mmcu=at90usb647
- LDFLAGS += -nostartfiles -nodefaultlibs
-endif
-
-ifeq ($(CONFIG_AVR_BUILDROOT),y)
- # NuttX buildroot GCC toolchain under Linux or Cygwin
- CROSSDEV = avr-nuttx-elf-
- MAXOPTIMIZATION = -O2
- ARCHCPUFLAGS = -mmcu=at90usb647
- LDFLAGS += -nostartfiles -nodefaultlibs
-endif
+include ${TOPDIR}/arch/avr/src/avr/Toolchain.defs
ifeq ($(WINTOOL),y)
# Windows-native toolchains
diff --git a/nuttx/configs/mirtoo/README.txt b/nuttx/configs/mirtoo/README.txt
index 488884ba5..89c137a03 100644
--- a/nuttx/configs/mirtoo/README.txt
+++ b/nuttx/configs/mirtoo/README.txt
@@ -323,6 +323,12 @@ Additional signals available via Peripheral Pin Selections (PPS)
Toolchains
==========
+ Note that in addition to the configuration options listed below, the
+ toolchain can be configured using the mconf utility ('make menuconfig')
+ or by passing CONFIG_MIPS32_TOOLCHAIN=<toolchain> to make, where
+ <toolchain> is one of GNU_ELF, MICROCHIPL, MICROCHIPW, MICROCHIPL_LITE,
+ MICROCHIPW_LITE, MICROCHIPOPENL or PINGUINOW as described below.
+
MPLAB/C32
---------
@@ -376,7 +382,7 @@ Toolchains
Note that the tools will have the prefix, mypic32- so, for example, the
compiler will be called mypic32-gcc.
- Pinguino mips-elf Toolchain
+ Pinguino mips-elf / Generic mips-elf Toolchain
---------------------------
Another option is the mips-elf toolchain used with the Pinguino project. This
@@ -390,12 +396,15 @@ Toolchains
configurations. Use one of these configuration options to select the Pinguino
mips-elf toolchain:
- CONFIG_PIC32MX_PINGUINOW - Pinguino mips-elf toolchain for Windows
- CONFIG_PIC32MX_PINGUINOL - Pinguino mips toolchain for Linux
+ CONFIG_PIC32MX_PINGUINOW - Pinguino mips-elf toolchain for Windows
+ CONFIG_MIPS32_TOOLCHAIN_GNU_ELF - mips-elf toolchain for Linux or OS X
And set the path appropriately in the setenv.sh file. These tool configurations
are untested -- expect some additional integration issues. Good luck!
+ This configuration will also work with any generic mips-elf GCC past version
+ 4.6 or so.
+
MPLAB/C32 vs MPLABX/X32
-----------------------
diff --git a/nuttx/configs/ntosd-dm320/README.txt b/nuttx/configs/ntosd-dm320/README.txt
index 1a6a38e7c..d85e53525 100644
--- a/nuttx/configs/ntosd-dm320/README.txt
+++ b/nuttx/configs/ntosd-dm320/README.txt
@@ -54,7 +54,8 @@ GNU Toolchain Options
1. The CodeSourcery GNU toolchain,
2. The devkitARM GNU toolchain,
3. Raisonance GNU toolchain, or
- 4. The NuttX buildroot Toolchain (see below).
+ 4. The NuttX buildroot Toolchain (see below), or
+ 5. Any generic arm-none-eabi GNU toolchain.
All testing has been conducted using the NuttX buildroot toolchain. However,
the make system is setup to default to use the devkitARM toolchain. To use
@@ -65,11 +66,17 @@ GNU Toolchain Options
CONFIG_DM320_CODESOURCERYW=y : CodeSourcery under Windows
CONFIG_DM320_CODESOURCERYL=y : CodeSourcery under Linux
CONFIG_DM320_DEVKITARM=y : devkitARM under Windows
- CONFIG_DM320_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default)
+ CONFIG_DM320_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default)
+ CONFIG_ARM_TOOLCHAIN_GNU_EABI : Generic arm-none-eabi toolchain
If you are not using CONFIG_DM320_BUILDROOT, then you may also have to modify
the PATH in the setenv.h file if your make cannot find the tools.
+ The toolchain may also be set using the mconf utility (make menuconfig) or by
+ passing CONFIG_ARM_TOOLCHAIN=<toolchain> to make, where <toolchain> is one
+ of CODESOURCERYW, CODESOURCERYL, DEVKITARM, BUILDROOT or GNU_EABI as described
+ above.
+
NOTE: the CodeSourcery (for Windows), devkitARM, and Raisonance toolchains are
Windows native toolchains. The CodeSourcey (for Linux) and NuttX buildroot
toolchains are Cygwin and/or Linux native toolchains. There are several limitations
@@ -105,6 +112,23 @@ GNU Toolchain Options
NOTE 2: The devkitARM toolchain includes a version of MSYS make. Make sure that
the paths to Cygwin's /bin and /usr/bin directories appear BEFORE the devkitARM
path or will get the wrong version of make.
+
+ Generic arm-none-eabi GNU Toolchain
+ -----------------------------------
+ There are a number of toolchain projects providing support for ARMv4/v5
+ class processors, including:
+
+ GCC ARM Embedded
+ https://launchpad.net/gcc-arm-embedded
+
+ Summon ARM Toolchain
+ https://github.com/esden/summon-arm-toolchain
+
+ Yagarto
+ http://www.yagarto.de
+
+ Others exist for various Linux distributions, MacPorts, etc. Any version
+ based on GCC 4.6.3 or later should work.
IDEs
^^^^
diff --git a/nuttx/configs/ntosd-dm320/nettest/Make.defs b/nuttx/configs/ntosd-dm320/nettest/Make.defs
index 8c5b7e93b..86dd3f815 100644
--- a/nuttx/configs/ntosd-dm320/nettest/Make.defs
+++ b/nuttx/configs/ntosd-dm320/nettest/Make.defs
@@ -35,30 +35,7 @@
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
-
-# Setup for the selected toolchain
-
-ifeq ($(CONFIG_DM320_CODESOURCERYW),y)
- # CodeSourcery under Windows
- CROSSDEV = arm-none-eabi-
- WINTOOL = y
- MAXOPTIMIZATION = -O2
-endif
-ifeq ($(CONFIG_DM320_CODESOURCERYL),y)
- # CodeSourcery under Linux
- CROSSDEV = arm-none-eabi-
- MAXOPTIMIZATION = -O2
-endif
-ifeq ($(CONFIG_DM320_DEVKITARM),y)
- # devkitARM under Windows
- CROSSDEV = arm-eabi-
- WINTOOL = y
-endif
-ifeq ($(CONFIG_DM320_BUILDROOT),y)
- # NuttX buildroot under Linux or Cygwin
- CROSSDEV = arm-nuttx-elf-
- MAXOPTIMIZATION = -Os
-endif
+include ${TOPDIR}/arch/arm/src/arm/Toolchain.defs
ifeq ($(WINTOOL),y)
# Windows-native toolchains
diff --git a/nuttx/configs/ntosd-dm320/nsh/Make.defs b/nuttx/configs/ntosd-dm320/nsh/Make.defs
index fa6149406..088dc7976 100644
--- a/nuttx/configs/ntosd-dm320/nsh/Make.defs
+++ b/nuttx/configs/ntosd-dm320/nsh/Make.defs
@@ -35,30 +35,7 @@
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
-
-# Setup for the selected toolchain
-
-ifeq ($(CONFIG_DM320_CODESOURCERYW),y)
- # CodeSourcery under Windows
- CROSSDEV = arm-none-eabi-
- WINTOOL = y
- MAXOPTIMIZATION = -O2
-endif
-ifeq ($(CONFIG_DM320_CODESOURCERYL),y)
- # CodeSourcery under Linux
- CROSSDEV = arm-none-eabi-
- MAXOPTIMIZATION = -O2
-endif
-ifeq ($(CONFIG_DM320_DEVKITARM),y)
- # devkitARM under Windows
- CROSSDEV = arm-eabi-
- WINTOOL = y
-endif
-ifeq ($(CONFIG_DM320_BUILDROOT),y)
- # NuttX buildroot under Linux or Cygwin
- CROSSDEV = arm-nuttx-elf-
- MAXOPTIMIZATION = -Os
-endif
+include ${TOPDIR}/arch/arm/src/arm/Toolchain.defs
ifeq ($(WINTOOL),y)
# Windows-native toolchains
diff --git a/nuttx/configs/ntosd-dm320/ostest/Make.defs b/nuttx/configs/ntosd-dm320/ostest/Make.defs
index 9b2ab9e5e..9312ae060 100644
--- a/nuttx/configs/ntosd-dm320/ostest/Make.defs
+++ b/nuttx/configs/ntosd-dm320/ostest/Make.defs
@@ -35,30 +35,7 @@
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
-
-# Setup for the selected toolchain
-
-ifeq ($(CONFIG_DM320_CODESOURCERYW),y)
- # CodeSourcery under Windows
- CROSSDEV = arm-none-eabi-
- WINTOOL = y
- MAXOPTIMIZATION = -O2
-endif
-ifeq ($(CONFIG_DM320_CODESOURCERYL),y)
- # CodeSourcery under Linux
- CROSSDEV = arm-none-eabi-
- MAXOPTIMIZATION = -O2
-endif
-ifeq ($(CONFIG_DM320_DEVKITARM),y)
- # devkitARM under Windows
- CROSSDEV = arm-eabi-
- WINTOOL = y
-endif
-ifeq ($(CONFIG_DM320_BUILDROOT),y)
- # NuttX buildroot under Linux or Cygwin
- CROSSDEV = arm-nuttx-elf-
- MAXOPTIMIZATION = -Os
-endif
+include ${TOPDIR}/arch/arm/src/arm/Toolchain.defs
ifeq ($(WINTOOL),y)
# Windows-native toolchains
diff --git a/nuttx/configs/ntosd-dm320/poll/Make.defs b/nuttx/configs/ntosd-dm320/poll/Make.defs
index 69c20da94..fb208f85c 100644
--- a/nuttx/configs/ntosd-dm320/poll/Make.defs
+++ b/nuttx/configs/ntosd-dm320/poll/Make.defs
@@ -35,30 +35,7 @@
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
-
-# Setup for the selected toolchain
-
-ifeq ($(CONFIG_DM320_CODESOURCERYW),y)
- # CodeSourcery under Windows
- CROSSDEV = arm-none-eabi-
- WINTOOL = y
- MAXOPTIMIZATION = -O2
-endif
-ifeq ($(CONFIG_DM320_CODESOURCERYL),y)
- # CodeSourcery under Linux
- CROSSDEV = arm-none-eabi-
- MAXOPTIMIZATION = -O2
-endif
-ifeq ($(CONFIG_DM320_DEVKITARM),y)
- # devkitARM under Windows
- CROSSDEV = arm-eabi-
- WINTOOL = y
-endif
-ifeq ($(CONFIG_DM320_BUILDROOT),y)
- # NuttX buildroot under Linux or Cygwin
- CROSSDEV = arm-nuttx-elf-
- MAXOPTIMIZATION = -Os
-endif
+include ${TOPDIR}/arch/arm/src/arm/Toolchain.defs
ifeq ($(WINTOOL),y)
# Windows-native toolchains
diff --git a/nuttx/configs/ntosd-dm320/thttpd/Make.defs b/nuttx/configs/ntosd-dm320/thttpd/Make.defs
index 252416f6b..cc62a030a 100644
--- a/nuttx/configs/ntosd-dm320/thttpd/Make.defs
+++ b/nuttx/configs/ntosd-dm320/thttpd/Make.defs
@@ -35,30 +35,7 @@
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
-
-# Setup for the selected toolchain
-
-ifeq ($(CONFIG_DM320_CODESOURCERYW),y)
- # CodeSourcery under Windows
- CROSSDEV = arm-none-eabi-
- WINTOOL = y
- MAXOPTIMIZATION = -O2
-endif
-ifeq ($(CONFIG_DM320_CODESOURCERYL),y)
- # CodeSourcery under Linux
- CROSSDEV = arm-none-eabi-
- MAXOPTIMIZATION = -O2
-endif
-ifeq ($(CONFIG_DM320_DEVKITARM),y)
- # devkitARM under Windows
- CROSSDEV = arm-eabi-
- WINTOOL = y
-endif
-ifeq ($(CONFIG_DM320_BUILDROOT),y)
- # NuttX buildroot under Linux or Cygwin
- CROSSDEV = arm-nuttx-elf-
- MAXOPTIMIZATION = -Os
-endif
+include ${TOPDIR}/arch/arm/src/arm/Toolchain.defs
ifeq ($(WINTOOL),y)
# Windows-native toolchains
diff --git a/nuttx/configs/ntosd-dm320/udp/Make.defs b/nuttx/configs/ntosd-dm320/udp/Make.defs
index 0cdb9f05d..1c8893289 100644
--- a/nuttx/configs/ntosd-dm320/udp/Make.defs
+++ b/nuttx/configs/ntosd-dm320/udp/Make.defs
@@ -35,30 +35,7 @@
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
-
-# Setup for the selected toolchain
-
-ifeq ($(CONFIG_DM320_CODESOURCERYW),y)
- # CodeSourcery under Windows
- CROSSDEV = arm-none-eabi-
- WINTOOL = y
- MAXOPTIMIZATION = -O2
-endif
-ifeq ($(CONFIG_DM320_CODESOURCERYL),y)
- # CodeSourcery under Linux
- CROSSDEV = arm-none-eabi-
- MAXOPTIMIZATION = -O2
-endif
-ifeq ($(CONFIG_DM320_DEVKITARM),y)
- # devkitARM under Windows
- CROSSDEV = arm-eabi-
- WINTOOL = y
-endif
-ifeq ($(CONFIG_DM320_BUILDROOT),y)
- # NuttX buildroot under Linux or Cygwin
- CROSSDEV = arm-nuttx-elf-
- MAXOPTIMIZATION = -Os
-endif
+include ${TOPDIR}/arch/arm/src/arm/Toolchain.defs
ifeq ($(WINTOOL),y)
# Windows-native toolchains
diff --git a/nuttx/configs/ntosd-dm320/uip/Make.defs b/nuttx/configs/ntosd-dm320/uip/Make.defs
index 64bb4494b..6d2a223df 100644
--- a/nuttx/configs/ntosd-dm320/uip/Make.defs
+++ b/nuttx/configs/ntosd-dm320/uip/Make.defs
@@ -35,30 +35,7 @@
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
-
-# Setup for the selected toolchain
-
-ifeq ($(CONFIG_DM320_CODESOURCERYW),y)
- # CodeSourcery under Windows
- CROSSDEV = arm-none-eabi-
- WINTOOL = y
- MAXOPTIMIZATION = -O2
-endif
-ifeq ($(CONFIG_DM320_CODESOURCERYL),y)
- # CodeSourcery under Linux
- CROSSDEV = arm-none-eabi-
- MAXOPTIMIZATION = -O2
-endif
-ifeq ($(CONFIG_DM320_DEVKITARM),y)
- # devkitARM under Windows
- CROSSDEV = arm-eabi-
- WINTOOL = y
-endif
-ifeq ($(CONFIG_DM320_BUILDROOT),y)
- # NuttX buildroot under Linux or Cygwin
- CROSSDEV = arm-nuttx-elf-
- MAXOPTIMIZATION = -Os
-endif
+include ${TOPDIR}/arch/arm/src/arm/Toolchain.defs
ifeq ($(WINTOOL),y)
# Windows-native toolchains
diff --git a/nuttx/configs/olimex-lpc2378/nsh/Make.defs b/nuttx/configs/olimex-lpc2378/nsh/Make.defs
index 5fba7e214..a7fce92f4 100644
--- a/nuttx/configs/olimex-lpc2378/nsh/Make.defs
+++ b/nuttx/configs/olimex-lpc2378/nsh/Make.defs
@@ -40,30 +40,7 @@
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
-
-# Setup for the selected toolchain
-
-ifeq ($(CONFIG_OLIMEX_LPC2378_CODESOURCERYW),y)
- # CodeSourcery under Windows
- CROSSDEV = arm-none-eabi-
- WINTOOL = y
- MAXOPTIMIZATION = -O2
-endif
-ifeq ($(CONFIG_OLIMEX_LPC2378_CODESOURCERYL),y)
- # CodeSourcery under Linux
- CROSSDEV = arm-none-eabi-
- MAXOPTIMIZATION = -O2
-endif
-ifeq ($(CONFIG_OLIMEX_LPC2378_DEVKITARM),y)
- # devkitARM under Windows
- CROSSDEV = arm-eabi-
- WINTOOL = y
-endif
-ifeq ($(CONFIG_OLIMEX_LPC2378_BUILDROOT),y)
- # NuttX buildroot under Linux or Cygwin
- CROSSDEV = arm-nuttx-elf-
- MAXOPTIMIZATION = -Os
-endif
+include ${TOPDIR}/arch/arm/src/arm/Toolchain.defs
ifeq ($(WINTOOL),y)
# Windows-native toolchains
diff --git a/nuttx/configs/olimex-lpc2378/ostest/Make.defs b/nuttx/configs/olimex-lpc2378/ostest/Make.defs
index 2c007cd39..2d8218bad 100644
--- a/nuttx/configs/olimex-lpc2378/ostest/Make.defs
+++ b/nuttx/configs/olimex-lpc2378/ostest/Make.defs
@@ -40,30 +40,7 @@
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
-
-# Setup for the selected toolchain
-
-ifeq ($(CONFIG_OLIMEX_LPC2378_CODESOURCERYW),y)
- # CodeSourcery under Windows
- CROSSDEV = arm-none-eabi-
- WINTOOL = y
- MAXOPTIMIZATION = -O2
-endif
-ifeq ($(CONFIG_OLIMEX_LPC2378_CODESOURCERYL),y)
- # CodeSourcery under Linux
- CROSSDEV = arm-none-eabi-
- MAXOPTIMIZATION = -O2
-endif
-ifeq ($(CONFIG_OLIMEX_LPC2378_DEVKITARM),y)
- # devkitARM under Windows
- CROSSDEV = arm-eabi-
- WINTOOL = y
-endif
-ifeq ($(CONFIG_OLIMEX_LPC2378_BUILDROOT),y)
- # NuttX buildroot under Linux or Cygwin
- CROSSDEV = arm-nuttx-elf-
- MAXOPTIMIZATION = -Os
-endif
+include ${TOPDIR}/arch/arm/src/arm/Toolchain.defs
ifeq ($(WINTOOL),y)
# Windows-native toolchains
diff --git a/nuttx/configs/stm3220g-eval/README.txt b/nuttx/configs/stm3220g-eval/README.txt
index 1e3388e70..8695dbb89 100644
--- a/nuttx/configs/stm3220g-eval/README.txt
+++ b/nuttx/configs/stm3220g-eval/README.txt
@@ -26,7 +26,7 @@ Contents
Development Environment
=======================
- Either Linux or Cygwin on Windows can be used for the development environment.
+ Linux, OS X or Cygwin on Windows can be used for the development environment.
The source has been built only using the GNU toolchain (see below). Other
toolchains will likely cause problems. Testing was performed using the Cygwin
environment because the Raisonance R-Link emulatator and some RIDE7 development tools
@@ -43,8 +43,9 @@ GNU Toolchain Options
1. The CodeSourcery GNU toolchain,
2. The Atollic Toolchain,
3. The devkitARM GNU toolchain,
- 4. Raisonance GNU toolchain, or
- 5. The NuttX buildroot Toolchain (see below).
+ 4. Raisonance GNU toolchain,
+ 5. The NuttX buildroot Toolchain (see below), or
+ 6. Any generic arm-none-eabi GNU toolchain.
Most testing has been conducted using the CodeSourcery toolchain for Windows and
that is the default toolchain in most configurations. To use the Atollic
@@ -59,10 +60,16 @@ GNU Toolchain Options
CONFIG_STM32_DEVKITARM=y : devkitARM under Windows
CONFIG_STM32_RAISONANCE=y : Raisonance RIDE7 under Windows
CONFIG_STM32_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default)
+ CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI : Generic arm-none-eabi toolchain
If you change the default toolchain, then you may also have to modify the PATH in
the setenv.h file if your make cannot find the tools.
+ The toolchain may also be set using the mconf utility (make menuconfig) or by
+ passing CONFIG_ARMV7M_TOOLCHAIN=<toolchain> to make, where <toolchain> is one
+ of CODESOURCERYW, CODESOURCERYL, ATOLLOC, DEVKITARM, RAISONANCE, BUILDROOT or
+ GNU_EABI as described above.
+
NOTE: the CodeSourcery (for Windows), Atollic, devkitARM, and Raisonance toolchains are
Windows native toolchains. The CodeSourcey (for Linux) and NuttX buildroot
toolchains are Cygwin and/or Linux native toolchains. There are several limitations
@@ -133,6 +140,26 @@ GNU Toolchain Options
the paths to Cygwin's /bin and /usr/bin directories appear BEFORE the devkitARM
path or will get the wrong version of make.
+ Generic arm-none-eabi GNU Toolchain
+ -----------------------------------
+ There are a number of toolchain projects providing support for the Cortex-M
+ class processors, including:
+
+ GCC ARM Embedded
+ https://launchpad.net/gcc-arm-embedded
+
+ Thumb2 Newlib Toolchain
+ https://github.com/EliasOenal/TNT
+
+ Summon ARM Toolchain
+ https://github.com/esden/summon-arm-toolchain
+
+ Yagarto
+ http://www.yagarto.de
+
+ Others exist for various Linux distributions, MacPorts, etc. Any version
+ based on GCC 4.6.3 or later should work.
+
IDEs
====
diff --git a/nuttx/configs/teensy/README.txt b/nuttx/configs/teensy/README.txt
index 30349e1ff..951f4a87e 100644
--- a/nuttx/configs/teensy/README.txt
+++ b/nuttx/configs/teensy/README.txt
@@ -201,7 +201,13 @@ Toolchains
There are several toolchain options. However, testing has been performed
using *only* the NuttX buildroot toolchain described below. Therefore,
-the NuttX buildroot toolchain is the recommended choice:
+the NuttX buildroot toolchain is the recommended choice.
+
+The toolchain may be selected using the mconf tool (via 'make menuconfig'),
+by editing the existing configuration file (defconfig), or by overriding
+the toolchain on the make commandline with CONFIG_AVR_TOOLCHAIN=<toolchain>.
+
+The valid values for <toolchain> are BUILDROOT, CROSSPACK, LINUXGCC and WINAVR.
Buildroot:
@@ -239,6 +245,14 @@ Linux:
After configuring NuttX, make sure that CONFIG_AVR_LINUXGCC=y is set in your
.config file.
+Mac OS X:
+
+ For Mac OS X, the CrossPack for AVR toolchain is available from:
+
+ http://www.obdev.at/products/crosspack/index.html
+
+ This toolchain is functionally equivalent to the Linux GCC toolchain.
+
Windows Native Toolchains
^^^^^^^^^^^^^^^^^^^^^^^^^
diff --git a/nuttx/configs/teensy/hello/Make.defs b/nuttx/configs/teensy/hello/Make.defs
index 9c7cb8268..d09279a8d 100644
--- a/nuttx/configs/teensy/hello/Make.defs
+++ b/nuttx/configs/teensy/hello/Make.defs
@@ -35,33 +35,7 @@
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
-
-# Setup for the selected toolchain
-
-ifeq ($(CONFIG_AVR_WINAVR),y)
- # WinAVR toolchain under Windows/Cygwin
- CROSSDEV = avr-
- WINTOOL = y
- MAXOPTIMIZATION = -O2
- ARCHCPUFLAGS = -mmcu=at90usb1286
- LDFLAGS += -nostartfiles -nodefaultlibs
-endif
-
-ifeq ($(CONFIG_AVR_LINUXGCC),y)
- # GCC toolchain under Linux
- CROSSDEV = avr-
- MAXOPTIMIZATION = -O2
- ARCHCPUFLAGS = -mmcu=at90usb1286
- LDFLAGS += -nostartfiles -nodefaultlibs
-endif
-
-ifeq ($(CONFIG_AVR_BUILDROOT),y)
- # NuttX buildroot GCC toolchain under Linux or Cygwin
- CROSSDEV = avr-nuttx-elf-
- MAXOPTIMIZATION = -O2
- ARCHCPUFLAGS = -mmcu=at90usb1286
- LDFLAGS += -nostartfiles -nodefaultlibs
-endif
+include ${TOPDIR}/arch/avr/src/avr/Toolchain.defs
ifeq ($(WINTOOL),y)
# Windows-native toolchains
diff --git a/nuttx/configs/teensy/nsh/Make.defs b/nuttx/configs/teensy/nsh/Make.defs
index 63c9db51f..e65958cfe 100644
--- a/nuttx/configs/teensy/nsh/Make.defs
+++ b/nuttx/configs/teensy/nsh/Make.defs
@@ -35,33 +35,7 @@
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
-
-# Setup for the selected toolchain
-
-ifeq ($(CONFIG_AVR_WINAVR),y)
- # WinAVR toolchain under Windows/Cygwin
- CROSSDEV = avr-
- WINTOOL = y
- MAXOPTIMIZATION = -O2
- ARCHCPUFLAGS = -mmcu=at90usb1286
- LDFLAGS += -nostartfiles -nodefaultlibs
-endif
-
-ifeq ($(CONFIG_AVR_LINUXGCC),y)
- # GCC toolchain under Linux
- CROSSDEV = avr-
- MAXOPTIMIZATION = -O2
- ARCHCPUFLAGS = -mmcu=at90usb1286
- LDFLAGS += -nostartfiles -nodefaultlibs
-endif
-
-ifeq ($(CONFIG_AVR_BUILDROOT),y)
- # NuttX buildroot GCC toolchain under Linux or Cygwin
- CROSSDEV = avr-nuttx-elf-
- MAXOPTIMIZATION = -O2
- ARCHCPUFLAGS = -mmcu=at90usb1286
- LDFLAGS += -nostartfiles -nodefaultlibs
-endif
+include ${TOPDIR}/arch/avr/src/avr/Toolchain.defs
ifeq ($(WINTOOL),y)
# Windows-native toolchains
diff --git a/nuttx/configs/teensy/usbstorage/Make.defs b/nuttx/configs/teensy/usbstorage/Make.defs
index 6474a772e..ba3878521 100644
--- a/nuttx/configs/teensy/usbstorage/Make.defs
+++ b/nuttx/configs/teensy/usbstorage/Make.defs
@@ -35,33 +35,7 @@
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
-
-# Setup for the selected toolchain
-
-ifeq ($(CONFIG_AVR_WINAVR),y)
- # WinAVR toolchain under Windows/Cygwin
- CROSSDEV = avr-
- WINTOOL = y
- MAXOPTIMIZATION = -O2
- ARCHCPUFLAGS = -mmcu=at90usb1286
- LDFLAGS += -nostartfiles -nodefaultlibs
-endif
-
-ifeq ($(CONFIG_AVR_LINUXGCC),y)
- # GCC toolchain under Linux
- CROSSDEV = avr-
- MAXOPTIMIZATION = -O2
- ARCHCPUFLAGS = -mmcu=at90usb1286
- LDFLAGS += -nostartfiles -nodefaultlibs
-endif
-
-ifeq ($(CONFIG_AVR_BUILDROOT),y)
- # NuttX buildroot GCC toolchain under Linux or Cygwin
- CROSSDEV = avr-nuttx-elf-
- MAXOPTIMIZATION = -O2
- ARCHCPUFLAGS = -mmcu=at90usb1286
- LDFLAGS += -nostartfiles -nodefaultlibs
-endif
+include ${TOPDIR}/arch/avr/src/avr/Toolchain.defs
ifeq ($(WINTOOL),y)
# Windows-native toolchains
diff --git a/nuttx/tools/incdir.bat b/nuttx/tools/incdir.bat
index 093c5bd2e..f7383fc9a 100755
--- a/nuttx/tools/incdir.bat
+++ b/nuttx/tools/incdir.bat
@@ -36,14 +36,21 @@ rem
rem Handle command line options
set progname=%0
+set pathtype=user
:ArgLoop
-rem [-d] [-w] [-h]. [-w] and [-d] Ignored for compatibility with incdir.sh
+rem [-d] [-w] [-s] [-h]. [-w] and [-d] Ignored for compatibility with incdir.sh
if "%1"=="-d" goto :NextArg
if "%1"=="-w" goto :NextArg
if "%1"=="-h" goto :Usage
+
+if "%1"=="-s" (
+ set pathtype=system
+ goto :NextArg
+)
+
goto :CheckCompiler
:NextArg
@@ -97,21 +104,43 @@ if not exist %1 (
)
if "%fmt%"=="zds" goto :GenerateZdsPath
+if "%response%"=="" goto :FirstStdPath
+if "%pathtype%"=="system" goto :NextStdSystemPath
-if "%response"=="" (
- set response=-I "%1"
-) else (
- set response=%response% -I "%1"
-)
+set response=%response% -I "%1"
+goto :EndOfDirLoop
+
+:NextStdSystemPath
+
+set response=%response% -isystem "%1"
+goto :EndOfDirLoop
+
+:FirstStdPath
+
+if "%pathtype%"=="system" goto :FirstStdSystemPath
+set response=-I "%1"
+goto :EndOfDirLoop
+
+:FirstStdSystemPath
+
+set response=-isystem "%1"
goto :EndOfDirLoop
:GenerateZdsPath
-if "%response"=="" (
- set response=-usrinc:%1
-) else (
- set response=%response%;%1
-)
+if "%response%"=="" goto :FirstZdsPath
+set response=%response%;%1
+goto :EndOfDirLoop
+
+:FirstZdsPath
+
+if "%pathtype%"=="system" goto :FirstZdsSystemPath
+set response=-usrinc:%1
+goto :EndOfDirLoop
+
+:FirstZdsSystemPath
+
+set response=-stdinc:%1
:EndOfDirLoop
shift
@@ -120,7 +149,7 @@ goto :DirLoop
:Usage
echo %progname% is a tool for flexible generation of include path arguments for a
echo variety of different compilers in a variety of compilation environments
-echo USAGE: %progname% [-w] [-d] [-h] ^<compiler-path^> ^<dir1^> [^<dir2^> [^<dir3^> ...]]
+echo USAGE: %progname% [-w] [-d] [-s] [-h] ^<compiler-path^> ^<dir1^> [^<dir2^> [^<dir3^> ...]]
echo Where:
echo ^<compiler-path^>
echo The full path to your compiler
@@ -128,6 +157,9 @@ echo ^<dir1^> [^<dir2^> [^<dir3^> ...]]
echo A list of include directories
echo -w, -d
echo For compatibility with incdir.sh (ignored)
+echo -s
+echo Generate standard, system header file paths instead of normal user
+echo header file paths.
echo -h
echo Shows this help text and exits.
:End
diff --git a/nuttx/tools/incdir.sh b/nuttx/tools/incdir.sh
index 1e862aae1..af83f8517 100755
--- a/nuttx/tools/incdir.sh
+++ b/nuttx/tools/incdir.sh
@@ -36,6 +36,7 @@
progname=$0
wintool=n
+pathtype=user
usage="USAGE: $progname [-w] [-d] [-h] <compiler-path> <dir1> [<dir2> [<dir3> ...]]"
advice="Try '$progname -h' for more information"
@@ -47,6 +48,9 @@ while [ ! -z "$1" ]; do
-w )
wintool=y
;;
+ -s )
+ pathtype=system
+ ;;
-h )
echo "$progname is a tool for flexible generation of include path arguments for a"
echo "variety of different compilers in a variety of compilation environments"
@@ -61,6 +65,9 @@ while [ ! -z "$1" ]; do
echo " -w"
echo " The compiler is a Windows native tool and requires Windows"
echo " style pathnames like C:\\Program Files"
+ echo " -s"
+ echo " Generate standard, system header file paths instead of normal user"
+ echo " header file paths."
echo " -d"
echo " Enable script debug"
echo " -h"
@@ -158,11 +165,27 @@ exefile=`basename "$compiler"`
# a special output format as well as special paths
if [ "X$exefile" = "Xez8cc.exe" -o "X$exefile" = "Xzneocc.exe" -o "X$exefile" = "Xez80cc.exe" ]; then
- fmt=userinc
+ fmt=zds
else
fmt=std
fi
+# Select system or user header file path command line option
+
+if [ "X$fmt" = "Xzds" ]; then
+ if [ "X$pathtype" = "Xsystem" ]; then
+ cmdarg=-stdinc:
+ else
+ cmdarg=-usrinc:
+ fi
+else
+ if [ "X$pathtype" = "Xsystem" ]; then
+ cmdarg=-isystem
+ else
+ cmdarg=-I
+ fi
+fi
+
# Now process each directory in the directory list
unset response
@@ -186,26 +209,26 @@ for dir in $dirlist; do
# Handle the output using the selected format
- if [ "X$fmt" = "Xuserinc" ]; then
+ if [ "X$fmt" = "Xzds" ]; then
# Treat the first directory differently
if [ -z "$response" ]; then
- response="-usrinc:'"$path
+ response="${cmdarg}'"${path}
else
- response=$response":$path"
+ response=${response}":${path}"
fi
else
# Treat the first directory differently
if [ -z "$response" ]; then
- response=-I\"$path\"
+ response="${cmdarg} \"$path\""
else
- response=$response" -I\"$path\""
+ response="${response} ${cmdarg} \"$path\""
fi
fi
done
-if [ "X$fmt" = "Xuserinc" ]; then
+if [ "X$fmt" = "Xzds" ]; then
response=$response"'"
fi