From c3bc22f07cb203c5a577b80467c8469d2a5ae9cb Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 27 Sep 2012 15:29:53 +0000 Subject: Definitions for ARMv7-M AIRCR register, Fixes for ADS7843 and SSD1289 driver, Missing build logic for examples/watchdog git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5198 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 6 ++++++ nuttx/arch/arm/src/armv7-m/nvic.h | 8 ++++++++ nuttx/drivers/input/ads7843e.c | 23 ++++++++++++++++++++++- nuttx/drivers/lcd/ssd1289.c | 20 +++++++++++++++++++- 4 files changed, 55 insertions(+), 2 deletions(-) (limited to 'nuttx') diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index adb52afce..f472e87cd 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3419,4 +3419,10 @@ on the Shenzhou board. * graphics/nxmu: Correct some bad parameter checking that caused failures when DEBUG was enabled. + * arch/arm/src/armv7-m/nvic.h: Add bit definitions for the AIRCR + register. + * drivers/input/ads7843.c: Need semaphore protection in logic + that samples the position. + * drivers/lcd/ssd1289.c: On some platforms we are unable to + read the device ID -- reason unknown; workaround in place. diff --git a/nuttx/arch/arm/src/armv7-m/nvic.h b/nuttx/arch/arm/src/armv7-m/nvic.h index 1d30c5f7c..ae56118c9 100644 --- a/nuttx/arch/arm/src/armv7-m/nvic.h +++ b/nuttx/arch/arm/src/armv7-m/nvic.h @@ -500,6 +500,14 @@ #define NVIC_SYSHCON_BUSFAULTENA (1 << 17) /* Bit 17: BusFault enabled */ #define NVIC_SYSHCON_USGFAULTENA (1 << 18) /* Bit 18: UsageFault enabled */ +/* Application Interrupt and Reset Control Register (AIRCR) */ + /* Bit 0: Reserved */ +#define NVIC_AIRC_VECTCLRACTIVE (1 << 1) /* Bit 1: Reserved for debug use */ +#define NVIC_AIRC_SYSRESETREQ (1 << 2) /* Bit 2: System reset */ + /* Bits 3-14: Reserved */ +#define NVIC_AIRC_ENDIANNESS (1 << 15) /* Bit 15: 1=Big endian */ + /* Bits 16-31: Reserved */ + /* Debug Exception and Monitor Control Register (DEMCR) */ #define NVIC_DEMCR_VCCORERESET (1 << 0) /* Bit 0: Reset Vector Catch */ diff --git a/nuttx/drivers/input/ads7843e.c b/nuttx/drivers/input/ads7843e.c index 07e5e515d..679c25113 100644 --- a/nuttx/drivers/input/ads7843e.c +++ b/nuttx/drivers/input/ads7843e.c @@ -555,6 +555,7 @@ static void ads7843e_worker(FAR void *arg) FAR struct ads7843e_dev_s *priv = (FAR struct ads7843e_dev_s *)arg; FAR struct ads7843e_config_s *config; bool pendown; + int ret; ASSERT(priv != NULL); @@ -565,10 +566,26 @@ static void ads7843e_worker(FAR void *arg) config = priv->config; DEBUGASSERT(config != NULL); - /* Disable the watchdog timer */ + /* Disable the watchdog timer. This is safe because it is started only + * by this function and this function is serialized on the worker thread. + */ wd_cancel(priv->wdog); + /* Get exclusive access to the driver data structure */ + + do + { + ret = sem_wait(&priv->devsem); + + /* This should only fail if the wait was canceled by an signal + * (and the worker thread will receive a lot of signals). + */ + + DEBUGASSERT(ret == OK || errno == EINTR); + } + while (ret < 0); + /* Check for pen up or down by reading the PENIRQ GPIO. */ pendown = config->pendown(config); @@ -645,6 +662,10 @@ static void ads7843e_worker(FAR void *arg) errout: (void)ads7843e_sendcmd(priv, ADS7843_CMD_ENABPINIRQ); config->enable(config, true); + + /* Release our lock on the state structure */ + + sem_post(&priv->devsem); } /**************************************************************************** diff --git a/nuttx/drivers/lcd/ssd1289.c b/nuttx/drivers/lcd/ssd1289.c index 3d5ba96d3..f5f11b87d 100644 --- a/nuttx/drivers/lcd/ssd1289.c +++ b/nuttx/drivers/lcd/ssd1289.c @@ -931,9 +931,27 @@ static inline int ssd1289_hwinitialize(FAR struct ssd1289_dev_s *priv) lcd->select(lcd); + /* Read the device ID. Skip verification of the device ID is the LCD is + * write-only. What choice do we have? + */ + #ifndef CONFIG_LCD_NOGETRUN id = ssd1289_readreg(lcd, SSD1289_DEVCODE); - lcddbg("LCD ID: %04x\n", id); + if (id != 0) + { + lcddbg("LCD ID: %04x\n", id); + } + + /* If we could not get the ID, then let's just assume that this is an SSD1289. + * Perhaps we have some early register access issues. This seems to happen. + * But then perhaps we should not even bother to read the device ID at all? + */ + + else + { + lcddbg("No LCD ID, assuming SSD1289\n"); + id = SSD1289_DEVCODE_VALUE; + } /* Check if the ID is for the SSD1289 */ -- cgit v1.2.3 From 7dc357a4e6e33773044b59b75d585f672f9649f8 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 27 Sep 2012 19:26:18 +0000 Subject: STM32 fixes for DM9161 PHY; Enhancements for ADS7843e touchscreen controller git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5199 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 11 +- nuttx/arch/arm/src/armv7-m/nvic.h | 22 ++-- nuttx/arch/arm/src/armv7-m/up_systemreset.c | 79 +++++++++++ nuttx/arch/arm/src/common/up_internal.h | 4 + nuttx/arch/arm/src/stm32/Kconfig | 1 + nuttx/arch/arm/src/stm32/Make.defs | 4 +- nuttx/arch/arm/src/stm32/stm32_eth.c | 79 +++++++++++ nuttx/configs/shenzhou/nsh/defconfig | 5 + nuttx/configs/shenzhou/nxwm/defconfig | 12 ++ nuttx/configs/shenzhou/src/up_touchscreen.c | 10 +- nuttx/drivers/input/Kconfig | 191 ++++++++++++++++++++++++++- nuttx/drivers/input/ads7843e.c | 198 ++++++++++++++++++---------- nuttx/drivers/input/ads7843e.h | 2 + nuttx/include/nuttx/input/ads7843e.h | 14 +- nuttx/include/nuttx/input/stmpe811.h | 2 +- nuttx/net/Kconfig | 6 + 16 files changed, 554 insertions(+), 86 deletions(-) create mode 100644 nuttx/arch/arm/src/armv7-m/up_systemreset.c (limited to 'nuttx') diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index f472e87cd..1e667ddcf 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3425,4 +3425,13 @@ that samples the position. * drivers/lcd/ssd1289.c: On some platforms we are unable to read the device ID -- reason unknown; workaround in place. - + * drivers/input/ads7843.c: Add thresholding options and an + option to swap X and Y positions. Fix some logic errors in + the SPI locking/selecting logic. + * arch/arm/src/armv7-m/up_systemreset.c: Add logic to reset + the Cortex-Mx using the AIRCR register. Contributed by Darcy + Gong. + * arch/arm/src/stm32/up_eth.c: Add logic specifically for the + DM9161 PHY. If the DM9161 failed to initialize, then use the + up_sysemreset() logic to reset the MCU. Contributed by Darcy + Gong. diff --git a/nuttx/arch/arm/src/armv7-m/nvic.h b/nuttx/arch/arm/src/armv7-m/nvic.h index ae56118c9..6bd842a76 100644 --- a/nuttx/arch/arm/src/armv7-m/nvic.h +++ b/nuttx/arch/arm/src/armv7-m/nvic.h @@ -175,7 +175,7 @@ #define NVIC_CPUID_BASE_OFFSET 0x0d00 /* CPUID base register */ #define NVIC_INTCTRL_OFFSET 0x0d04 /* Interrupt control state register */ #define NVIC_VECTAB_OFFSET 0x0d08 /* Vector table offset register */ -#define NVIC_AIRC_OFFSET 0x0d0c /* Application interrupt/reset contol registr */ +#define NVIC_AIRCR_OFFSET 0x0d0c /* Application interrupt/reset contol registr */ #define NVIC_SYSCON_OFFSET 0x0d10 /* System control register */ #define NVIC_CFGCON_OFFSET 0x0d14 /* Configuration control register */ #define NVIC_SYSH_PRIORITY_OFFSET(n) (0x0d14 + 4*((n) >> 2)) @@ -348,7 +348,7 @@ #define NVIC_CPUID_BASE (ARMV7M_NVIC_BASE + NVIC_CPUID_BASE_OFFSET) #define NVIC_INTCTRL (ARMV7M_NVIC_BASE + NVIC_INTCTRL_OFFSET) #define NVIC_VECTAB (ARMV7M_NVIC_BASE + NVIC_VECTAB_OFFSET) -#define NVIC_AIRC (ARMV7M_NVIC_BASE + NVIC_AIRC_OFFSET) +#define NVIC_AIRCR (ARMV7M_NVIC_BASE + NVIC_AIRCR_OFFSET) #define NVIC_SYSCON (ARMV7M_NVIC_BASE + NVIC_SYSCON_OFFSET) #define NVIC_CFGCON (ARMV7M_NVIC_BASE + NVIC_CFGCON_OFFSET) #define NVIC_SYSH_PRIORITY(n) (ARMV7M_NVIC_BASE + NVIC_SYSH_PRIORITY_OFFSET(n)) @@ -501,12 +501,18 @@ #define NVIC_SYSHCON_USGFAULTENA (1 << 18) /* Bit 18: UsageFault enabled */ /* Application Interrupt and Reset Control Register (AIRCR) */ - /* Bit 0: Reserved */ -#define NVIC_AIRC_VECTCLRACTIVE (1 << 1) /* Bit 1: Reserved for debug use */ -#define NVIC_AIRC_SYSRESETREQ (1 << 2) /* Bit 2: System reset */ - /* Bits 3-14: Reserved */ -#define NVIC_AIRC_ENDIANNESS (1 << 15) /* Bit 15: 1=Big endian */ - /* Bits 16-31: Reserved */ + +#define NVIC_AIRCR_VECTRESET (1 << 0) /* Bit 0: VECTRESET */ +#define NVIC_AIRCR_VECTCLRACTIVE (1 << 1) /* Bit 1: Reserved for debug use */ +#define NVIC_AIRCR_SYSRESETREQ (1 << 2) /* Bit 2: System reset */ + /* Bits 2-7: Reserved */ +#define NVIC_AIRCR_PRIGROUP_SHIFT (8) /* Bits 8-14: PRIGROUP */ +#define NVIC_AIRCR_PRIGROUP_MASK (7 << NVIC_AIRCR_PRIGROUP_SHIFT) +#define NVIC_AIRCR_ENDIANNESS (1 << 15) /* Bit 15: 1=Big endian */ +#define NVIC_AIRCR_VECTKEY_SHIFT (16) /* Bits 16-31: VECTKEY */ +#define NVIC_AIRCR_VECTKEY_MASK (0xffff << NVIC_AIRCR_VECTKEY_SHIFT) +#define NVIC_AIRCR_VECTKEYSTAT_SHIFT (16) /* Bits 16-31: VECTKEYSTAT */ +#define NVIC_AIRCR_VECTKEYSTAT_MASK (0xffff << NVIC_AIRCR_VECTKEYSTAT_SHIFT) /* Debug Exception and Monitor Control Register (DEMCR) */ diff --git a/nuttx/arch/arm/src/armv7-m/up_systemreset.c b/nuttx/arch/arm/src/armv7-m/up_systemreset.c new file mode 100644 index 000000000..0d7bd2736 --- /dev/null +++ b/nuttx/arch/arm/src/armv7-m/up_systemreset.c @@ -0,0 +1,79 @@ +/**************************************************************************** + * arch/arm/src/armv7-m/up_systemreset.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Darcy Gong + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include "up_arch.h" +#include "nvic.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + + /**************************************************************************** + * Public Types + ****************************************************************************/ + +/**************************************************************************** + * Public functions + ****************************************************************************/ + +void up_systemreset(void) +{ + uint32_t regval; + + /* Set up for the system reset, retaining the priority group from the + * the AIRCR register. + */ + + regval = getreg32(NVIC_AIRCR) & NVIC_AIRCR_PRIGROUP_MASK; + regval |= ((0x5fa << NVIC_AIRCR_VECTKEY_SHIFT) | NVIC_AIRCR_SYSRESETREQ); + putreg32(regval, NVIC_AIRCR); + + /* Ensure completion of memory accesses */ + + __asm volatile ("dsb"); + + /* Wait for the reset */ + + for (;;); +} diff --git a/nuttx/arch/arm/src/common/up_internal.h b/nuttx/arch/arm/src/common/up_internal.h index 9f20775c0..42142c5e8 100644 --- a/nuttx/arch/arm/src/common/up_internal.h +++ b/nuttx/arch/arm/src/common/up_internal.h @@ -241,6 +241,10 @@ extern void up_pminitialize(void); # define up_pminitialize() #endif +#if defined(CONFIG_ARCH_CORTEXM3) || defined(CONFIG_ARCH_CORTEXM4) +extern void up_systemreset(void) noreturn_function; +#endif + /* Interrupt handling *******************************************************/ extern void up_irqinitialize(void); diff --git a/nuttx/arch/arm/src/stm32/Kconfig b/nuttx/arch/arm/src/stm32/Kconfig index 8d93fb104..fe89119a4 100644 --- a/nuttx/arch/arm/src/stm32/Kconfig +++ b/nuttx/arch/arm/src/stm32/Kconfig @@ -269,6 +269,7 @@ config STM32_ETHMAC bool "Ethernet MAC" default n depends on STM32_CONNECTIVITYLINE || STM32_STM32F20XX || STM32_STM32F40XX + select ARCH_HAVE_PHY config STM32_FSMC bool "FSMC" diff --git a/nuttx/arch/arm/src/stm32/Make.defs b/nuttx/arch/arm/src/stm32/Make.defs index 24af16c95..e52962977 100644 --- a/nuttx/arch/arm/src/stm32/Make.defs +++ b/nuttx/arch/arm/src/stm32/Make.defs @@ -45,8 +45,8 @@ CMN_CSRCS = up_assert.c up_blocktask.c up_copystate.c \ up_initialize.c up_initialstate.c up_interruptcontext.c \ up_memfault.c up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c \ up_releasepending.c up_releasestack.c up_reprioritizertr.c \ - up_schedulesigaction.c up_sigdeliver.c up_unblocktask.c \ - up_usestack.c up_doirq.c up_hardfault.c up_svcall.c + up_schedulesigaction.c up_sigdeliver.c up_systemreset.c \ + up_unblocktask.c up_usestack.c up_doirq.c up_hardfault.c up_svcall.c ifeq ($(CONFIG_ARMV7M_CMNVECTOR),y) CMN_ASRCS += up_exception.S diff --git a/nuttx/arch/arm/src/stm32/stm32_eth.c b/nuttx/arch/arm/src/stm32/stm32_eth.c index 2e892c9e5..81345fabf 100644 --- a/nuttx/arch/arm/src/stm32/stm32_eth.c +++ b/nuttx/arch/arm/src/stm32/stm32_eth.c @@ -664,6 +664,9 @@ static void stm32_rxdescinit(FAR struct stm32_ethmac_s *priv); static int stm32_phyread(uint16_t phydevaddr, uint16_t phyregaddr, uint16_t *value); static int stm32_phywrite(uint16_t phydevaddr, uint16_t phyregaddr, uint16_t value); +#ifdef CONFIG_PHY_DM9161 +static inline int stm32_dm9161(FAR struct stm32_ethmac_s *priv); +#endif static int stm32_phyinit(FAR struct stm32_ethmac_s *priv); /* MAC/DMA Initialization */ @@ -2479,6 +2482,72 @@ static int stm32_phywrite(uint16_t phydevaddr, uint16_t phyregaddr, uint16_t val return -ETIMEDOUT; } +/**************************************************************************** + * Function: stm32_dm9161 + * + * Description: + * Special workaround for the Davicom DM9161 PHY is required. On power, + * up, the PHY is not usually configured correctly but will work after + * a powered-up reset. This is really a workaround for some more + * fundamental issue with the PHY clocking initialization, but the + * root cause has not been studied (nor will it be with this workaround). + * + * Parameters: + * priv - A reference to the private driver state structure + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_PHY_DM9161 +static inline int stm32_dm9161(FAR struct stm32_ethmac_s *priv) +{ + uint16_t phyval; + int ret; + + /* Read the PHYID1 register; A failure to read the PHY ID is one + * indication that check if the DM9161 PHY CHIP is not ready. + */ + + ret = stm32_phyread(CONFIG_STM32_PHYADDR, MII_PHYID1, &phyval); + if (ret < 0) + { + ndbg("Failed to read the PHY ID1: %d\n", ret); + return ret; + } + + /* If we failed to read the PHY ID1 register, the reset the MCU to recover */ + + else if (phyval == 0xffff) + { + up_systemreset(); + } + + nvdbg("PHY ID1: 0x%04X\n", phyval); + + /* Now check the "DAVICOM Specified Configuration Register (DSCR)", Register 16 */ + + ret = stm32_phyread(CONFIG_STM32_PHYADDR, 16, &phyval); + if (ret < 0) + { + ndbg("Failed to read the PHY Register 0x10: %d\n", ret); + return ret; + } + + /* Bit 8 of the DSCR register is zero, the the DM9161 has not selected RMII. + * If RMII is not selected, then reset the MCU to recover. + */ + + else if ((phyval & (1 << 8)) == 0) + { + up_systemreset(); + } + + return OK; +} +#endif + /**************************************************************************** * Function: stm32_phyinit * @@ -2524,6 +2593,16 @@ static int stm32_phyinit(FAR struct stm32_ethmac_s *priv) } up_mdelay(PHY_RESET_DELAY); + /* Special workaround for the Davicom DM9161 PHY is required. */ + +#ifdef CONFIG_PHY_DM9161 + ret = stm32_dm9161(priv); + if (ret < 0) + { + return ret; + } +#endif + /* Perform auto-negotion if so configured */ #ifdef CONFIG_STM32_AUTONEG diff --git a/nuttx/configs/shenzhou/nsh/defconfig b/nuttx/configs/shenzhou/nsh/defconfig index 3528f6d60..706881cc0 100644 --- a/nuttx/configs/shenzhou/nsh/defconfig +++ b/nuttx/configs/shenzhou/nsh/defconfig @@ -377,6 +377,11 @@ CONFIG_USART2_2STOP=0 # Networking Support # CONFIG_NET=y +CONFIG_ARCH_HAVE_PHY=y +# CONFIG_PHY_KS8721 is not set +# CONFIG_PHY_DP83848C is not set +# CONFIG_PHY_LAN8720 is not set +CONFIG_PHY_DM9161=y # CONFIG_NET_NOINTS is not set CONFIG_NET_MULTIBUFFER=y # CONFIG_NET_IPv6 is not set diff --git a/nuttx/configs/shenzhou/nxwm/defconfig b/nuttx/configs/shenzhou/nxwm/defconfig index 29c83730e..b529907c1 100644 --- a/nuttx/configs/shenzhou/nxwm/defconfig +++ b/nuttx/configs/shenzhou/nxwm/defconfig @@ -359,6 +359,13 @@ CONFIG_RTC=y CONFIG_INPUT=y # CONFIG_INPUT_TSC2007 is not set CONFIG_INPUT_ADS7843E=y +# CONFIG_ADS7843E_MULTIPLE is not set +CONFIG_ADS7843E_SPIMODE=0 +CONFIG_ADS7843E_FREQUENCY=100000 +# CONFIG_ADS7843E_SWAPXY is not set +CONFIG_ADS7843E_THRESHX=12 +CONFIG_ADS7843E_THRESHY=12 +# CONFIG_INPUT_STMPE811 is not set CONFIG_LCD=y # CONFIG_LCD_NOGETRUN is not set CONFIG_LCD_MAXCONTRAST=1 @@ -418,6 +425,11 @@ CONFIG_USART2_2STOP=0 # Networking Support # CONFIG_NET=y +CONFIG_ARCH_HAVE_PHY=y +# CONFIG_PHY_KS8721 is not set +# CONFIG_PHY_DP83848C is not set +# CONFIG_PHY_LAN8720 is not set +CONFIG_PHY_DM9161=y # CONFIG_NET_NOINTS is not set CONFIG_NET_MULTIBUFFER=y # CONFIG_NET_IPv6 is not set diff --git a/nuttx/configs/shenzhou/src/up_touchscreen.c b/nuttx/configs/shenzhou/src/up_touchscreen.c index 7f6d49eb5..969b23be4 100644 --- a/nuttx/configs/shenzhou/src/up_touchscreen.c +++ b/nuttx/configs/shenzhou/src/up_touchscreen.c @@ -201,9 +201,17 @@ static void tsc_clear(FAR struct ads7843e_config_s *state) static bool tsc_busy(FAR struct ads7843e_config_s *state) { /* Hmmm... The ADS7843E BUSY pin is not brought out on the Shenzhou board. - * We will most certainly have to revisit this. + * We will most certainly have to revisit this. There is this cryptic + * statement in the XPT2046 spec: "No DCLK delay required with dedicated + * serial port." + * + * The busy state is used by the ADS7843E driver to control the delay + * between sending the command, then reading the returned data. */ +#if 0 + up_udelay(1600); /* 1.6MS */ +#endif return false; } diff --git a/nuttx/drivers/input/Kconfig b/nuttx/drivers/input/Kconfig index 9fde35ff6..1f345ee14 100644 --- a/nuttx/drivers/input/Kconfig +++ b/nuttx/drivers/input/Kconfig @@ -2,6 +2,7 @@ # For a description of the syntax of this configuration file, # see misc/tools/kconfig-language.txt. # + config INPUT_TSC2007 bool "TI TSC2007 touchscreen controller" default n @@ -9,7 +10,29 @@ config INPUT_TSC2007 ---help--- Enable support for the TI TSC2007 touchscreen controller - +if INPUT_TSC2007 + +config TSC2007_8BIT + bool "8-bit Conversions" + default n + ---help--- + Use faster, but less accurate, 8-bit conversions. Default: 12-bit conversions. + +config TSC2007_MULTIPLE + bool "Multiple TSC2007 Devices" + default n + ---help--- + Can be defined to support multiple TSC2007 devices on board. + +config TSC2007_NPOLLWAITERS + int "Number poll waiters" + default 4 + depends on !DISABLE_POLL + ---help--- + Maximum number of threads that can be waiting on poll() + +endif + config INPUT_ADS7843E bool "TI ADS7843/TSC2046 touchscreen controller" default n @@ -18,3 +41,169 @@ config INPUT_ADS7843E Enable support for the TI/Burr-Brown ADS7842 touchscreen controller. I believe that driver should be compatibile with the TI/Burr-Brown TSC2046 and XPT2046 touchscreen controllers as well. + +if INPUT_ADS7843E + +config ADS7843E_MULTIPLE + bool "Multiple ADS7843E Devices" + default n + ---help--- + Can be defined to support multiple ADS7843E devices on board. + +config ADS7843E_NPOLLWAITERS + int "Number poll waiters" + default 4 + depends on !DISABLE_POLL + ---help--- + Maximum number of threads that can be waiting on poll() + +config ADS7843E_SPIMODE + int "SPI mode" + default 0 + range 0,3 + ---help--- + Controls the SPI mode. The device should work in mode 0, but sometimes + you need to experiment. + +config ADS7843E_FREQUENCY + int "SPI frequency" + default 100000 + ---help--- + Define to use a different SPI bus frequency. + +config ADS7843E_SWAPXY + bool "Swap X/Y" + default n + ---help--- + Reverse the meaning of X and Y to handle different LCD orientations. + +config ADS7843E_THRESHX + int "X threshold" + default 12 + ---help--- + New touch positions will only be reported when the X or Y data changes by these + thresholds. This trades reduces data rate for some loss in dragging accuracy. For + 12-bit values so the raw ranges are 0-4095. So for example, if your display is + 320x240, then THRESHX=13 and THRESHY=17 would correspond to one pixel. Default: 12 + +config ADS7843E_THRESHY + int "Y threshold" + default 12 + ---help--- + New touch positions will only be reported when the X or Y data changes by these + thresholds. This trades reduces data rate for some loss in dragging accuracy. For + 12-bit values so the raw ranges are 0-4095. So for example, if your display is + 320x240, then THRESHX=13 and THRESHY=17 would correspond to one pixel. Default: 12 + +endif + +config INPUT_STMPE811 + bool "STMicro STMPE811 Driver" + default n + ---help--- + Enables support for the STMPE811 driver + +if INPUT_STMPE811 + +choice + prompt "STMPE Interface" + default STMPE811_I2C + +config STMPE811_SPI + bool "SPI Interface" + select SPI + ---help--- + Enables support for the SPI interface (not currently supported) + +config STMPE811_I2C + bool "STMPE811 I2C Interface" + select I2C + ---help--- + Enables support for the I2C interface + +endchoice + +config STMPE811_MULTIPLE + bool "Multiple STMPE811 Devices" + default n + ---help--- + Can be defined to support multiple STMPE811 devices on board. + +config STMPE811_NPOLLWAITERS + int "Number poll waiters" + default 4 + depends on !DISABLE_POLL + ---help--- + Maximum number of threads that can be waiting on poll() + +config STMPE811_TSC_DISABLE + bool "Disable STMPE811 Touchscreen Support" + default n + ---help--- + Disable driver touchscreen functionality. + +config STMPE811_SWAPXY + bool "Swap X/Y" + default n + depends on !STMPE811_TSC_DISABLE + ---help--- + Reverse the meaning of X and Y to handle different LCD orientations. + +config STMPE811_THRESHX + int "X threshold" + default 12 + depends on !STMPE811_TSC_DISABLE + ---help--- + STMPE811 touchscreen data comes in a a very high rate. New touch positions + will only be reported when the X or Y data changes by these thresholds. + This trades reduces data rate for some loss in dragging accuracy. The + STMPE811 is configure for 12-bit values so the raw ranges are 0-4095. So + for example, if your display is 320x240, then THRESHX=13 and THRESHY=17 + would correspond to one pixel. Default: 12 + +config STMPE811_THRESHY + int "Y threshold" + default 12 + depends on !STMPE811_TSC_DISABLE + ---help--- + STMPE811 touchscreen data comes in a a very high rate. New touch positions + will only be reported when the X or Y data changes by these thresholds. + This trades reduces data rate for some loss in dragging accuracy. The + STMPE811 is configure for 12-bit values so the raw ranges are 0-4095. So + for example, if your display is 320x240, then THRESHX=13 and THRESHY=17 + would correspond to one pixel. Default: 12 + +config STMPE811_ADC_DISABLE + bool "Disable STMPE811 ADC Support" + default y + ---help--- + Disable driver ADC functionality. + +config STMPE811_GPIO_DISABLE + bool "Disable STMPE811 GPIO Support" + default y + ---help--- + Disable driver GPIO functionality. + +config STMPE811_GPIOINT_DISABLE + bool "Disable STMPE811 GPIO Interrupt Support" + default y + depends on !STMPE811_GPIO_DISABLE + ---help--- + Disable driver GPIO interrupt functionlality (ignored if GPIO functionality is + disabled). + +config STMPE811_TEMP_DISABLE + bool "Disable STMPE811 Temperature Sensor Support" + default y + ---help--- + Disable driver temperature sensor functionality. + +config STMPE811_REGDEBUG + bool "Enable Register-Level STMPE811 Debug" + default n + depends on DEBUG + ---help--- + Enable very low register-level debug output. + +endif diff --git a/nuttx/drivers/input/ads7843e.c b/nuttx/drivers/input/ads7843e.c index 679c25113..ce45e4537 100644 --- a/nuttx/drivers/input/ads7843e.c +++ b/nuttx/drivers/input/ads7843e.c @@ -79,6 +79,12 @@ * Pre-processor Definitions ****************************************************************************/ +/* This is a value for the threshold that guantees a big difference on the + * first pendown (but can't overflow). + */ + +#define INVALID_THRESHOLD 0x1000 + /**************************************************************************** * Private Types ****************************************************************************/ @@ -88,13 +94,14 @@ ****************************************************************************/ /* Low-level SPI helpers */ -static inline void ads7843e_configspi(FAR struct spi_dev_s *spi); #ifdef CONFIG_SPI_OWNBUS -static inline void ads7843e_select(FAR struct spi_dev_s *spi); -static inline void ads7843e_deselect(FAR struct spi_dev_s *spi); +static inline void ads7843e_configspi(FAR struct spi_dev_s *spi); +# define ads7843e_lock(spi) +# define ads7843e_unlock(spi) #else -static void ads7843e_select(FAR struct spi_dev_s *spi); -static void ads7843e_deselect(FAR struct spi_dev_s *spi); +# define ads7843e_configspi(spi); +static void ads7843e_lock(FAR struct spi_dev_s *spi); +static void ads7843e_unlock(FAR struct spi_dev_s *spi); #endif static inline void ads7843e_waitbusy(FAR struct ads7843e_dev_s *priv); @@ -157,13 +164,12 @@ static struct ads7843e_dev_s *g_ads7843elist; ****************************************************************************/ /**************************************************************************** - * Function: ads7843e_select + * Function: ads7843e_lock * * Description: - * Select the SPI, locking and re-configuring if necessary. This function - * must be called before initiating any sequence of SPI operations. If we - * are sharing the SPI bus with other devices (CONFIG_SPI_OWNBUS undefined) - * then we need to lock and configure the SPI bus for each transfer. + * Lock the SPI bus and re-configure as necessary. This function must be + * to assure: (1) exclusive access to the SPI bus, and (2) to assure that + * the shared bus is properly configured for the touchscreen controller. * * Parameters: * spi - Reference to the SPI driver structure @@ -175,42 +181,35 @@ static struct ads7843e_dev_s *g_ads7843elist; * ****************************************************************************/ -#ifdef CONFIG_SPI_OWNBUS -static inline void ads7843e_select(FAR struct spi_dev_s *spi) +#ifndef CONFIG_SPI_OWNBUS +static void ads7843e_lock(FAR struct spi_dev_s *spi) { - /* We own the SPI bus, so just select the chip */ - - SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, true); -} -#else -static void ads7843e_select(FAR struct spi_dev_s *spi) -{ - /* Select ADS7843 chip (locking the SPI bus in case there are multiple - * devices competing for the SPI bus + /* Lock the SPI bus because there are multiple devices competing for the + * SPI bus */ (void)SPI_LOCK(spi, true); - SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, true); - /* Now make sure that the SPI bus is configured for the ADS7843 (it - * might have gotten configured for a different device while unlocked) + /* We have the lock. Now make sure that the SPI bus is configured for the + * ADS7843 (it might have gotten configured for a different device while + * unlocked) */ + SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, true); SPI_SETMODE(spi, CONFIG_ADS7843E_SPIMODE); SPI_SETBITS(spi, 8); SPI_SETFREQUENCY(spi, CONFIG_ADS7843E_FREQUENCY); + SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, false); } #endif /**************************************************************************** - * Function: ads7843e_deselect + * Function: ads7843e_unlock * * Description: - * De-select the SPI, unlocking as necessary. This function must be - * after completing a sequence of SPI operations. If we are sharing the SPI - * bus with other devices (CONFIG_SPI_OWNBUS undefined) then we need to - * un-lock the SPI bus for each transfer, possibly losing the current - * configuration. + * If we are sharing the SPI bus with other devices (CONFIG_SPI_OWNBUS + * undefined) then we need to un-lock the SPI bus for each transfer, + * possibly losing the current configuration. * * Parameters: * spi - Reference to the SPI driver structure @@ -222,19 +221,11 @@ static void ads7843e_select(FAR struct spi_dev_s *spi) * ****************************************************************************/ -#ifdef CONFIG_SPI_OWNBUS -static inline void ads7843e_deselect(FAR struct spi_dev_s *spi) -{ - /* We own the SPI bus, so just de-select the chip */ - - SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, false); -} -#else -static void ads7843e_deselect(FAR struct spi_dev_s *spi) +#ifndef CONFIG_SPI_OWNBUS +static void ads7843e_unlock(FAR struct spi_dev_s *spi) { - /* De-select ADS7843 chip and relinquish the SPI bus. */ + /* Relinquish the SPI bus. */ - SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, false); (void)SPI_LOCK(spi, false); } #endif @@ -258,23 +249,20 @@ static void ads7843e_deselect(FAR struct spi_dev_s *spi) * ****************************************************************************/ +#ifdef CONFIG_SPI_OWNBUS static inline void ads7843e_configspi(FAR struct spi_dev_s *spi) { - idbg("Mode: %d Bits: 8 Frequency: %d\n", - CONFIG_ADS7843E_SPIMODE, CONFIG_ADS7843E_FREQUENCY); - /* Configure SPI for the ADS7843. But only if we own the SPI bus. Otherwise, don't * bother because it might change. */ -#ifdef CONFIG_SPI_OWNBUS SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, true); SPI_SETMODE(spi, CONFIG_ADS7843E_SPIMODE); SPI_SETBITS(spi, 8); SPI_SETFREQUENCY(spi, CONFIG_ADS7843E_FREQUENCY); SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, false); -#endif } +#endif /**************************************************************************** * Name: ads7843e_waitbusy @@ -296,7 +284,7 @@ static uint16_t ads7843e_sendcmd(FAR struct ads7843e_dev_s *priv, uint8_t cmd) /* Select the ADS7843E */ - ads7843e_select(priv->spi); + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, true); /* Send the command */ @@ -306,7 +294,7 @@ static uint16_t ads7843e_sendcmd(FAR struct ads7843e_dev_s *priv, uint8_t cmd) /* Read the data */ SPI_RECVBLOCK(priv->spi, buffer, 2); - ads7843e_deselect(priv->spi); + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, false); result = ((uint16_t)buffer[0] << 8) | (uint16_t)buffer[1]; result = result >> 4; @@ -554,6 +542,10 @@ static void ads7843e_worker(FAR void *arg) { FAR struct ads7843e_dev_s *priv = (FAR struct ads7843e_dev_s *)arg; FAR struct ads7843e_config_s *config; + uint16_t x; + uint16_t y; + uint16_t xdiff; + uint16_t ydiff; bool pendown; int ret; @@ -572,6 +564,10 @@ static void ads7843e_worker(FAR void *arg) wd_cancel(priv->wdog); + /* Lock the SPI bus so that we have exclusive access */ + + ads7843e_lock(priv->spi); + /* Get exclusive access to the driver data structure */ do @@ -594,13 +590,20 @@ static void ads7843e_worker(FAR void *arg) if (!pendown) { - /* Ignore the interrupt if the pen was already up (CONTACT_NONE == pen up and - * already reported. CONTACT_UP == pen up, but not reported) + /* The pen is up.. reset thresholding variables. */ + + priv->threshx = INVALID_THRESHOLD; + priv->threshy = INVALID_THRESHOLD; + + /* Ignore the interrupt if the pen was already up (CONTACT_NONE == pen up + * and already reported; CONTACT_UP == pen up, but not reported) */ - if (priv->sample.contact == CONTACT_NONE) + if (priv->sample.contact == CONTACT_NONE || + priv->sample.contact == CONTACT_UP) + { - goto errout; + goto ignored; } /* The pen is up. NOTE: We know from a previous test, that this is a @@ -618,14 +621,57 @@ static void ads7843e_worker(FAR void *arg) else if (priv->sample.contact == CONTACT_UP) { - goto errout; + /* If we have not yet processed the last pen up event, then we + * cannot handle this pen down event. We will have to discard it. That + * should be okay because we will set the timer to to sample again + * later. + */ + + wd_start(priv->wdog, ADS7843E_WDOG_DELAY, ads7843e_wdog, 1, (uint32_t)priv); + goto ignored; } else { /* Handle pen down events. First, sample positional values. */ - priv->sample.x = ads7843e_sendcmd(priv, ADS7843_CMD_XPOSITION); - priv->sample.y = ads7843e_sendcmd(priv, ADS7843_CMD_YPOSITION); +#ifdef CONFIG_ADS7843E_SWAPXY + x = ads7843e_sendcmd(priv, ADS7843_CMD_YPOSITION); + y = ads7843e_sendcmd(priv, ADS7843_CMD_XPOSITION); +#else + x = ads7843e_sendcmd(priv, ADS7843_CMD_XPOSITION); + y = ads7843e_sendcmd(priv, ADS7843_CMD_YPOSITION); +#endif + + /* Perform a thresholding operation so that the results will be more stable. + * If the difference from the last sample is small, then ignore the event. + * REVISIT: Should a large change in pressure also generate a event? + */ + + xdiff = x > priv->threshx ? (x - priv->threshx) : (priv->threshx - x); + ydiff = y > priv->threshy ? (y - priv->threshy) : (priv->threshy - y); + + /* Continue to sample the position while the pen is down */ + + wd_start(priv->wdog, ADS7843E_WDOG_DELAY, ads7843e_wdog, 1, (uint32_t)priv); + + /* Check the thresholds. Bail if there is no significant difference */ + + if (xdiff < CONFIG_ADS7843E_THRESHX && ydiff < CONFIG_ADS7843E_THRESHY) + { + /* Little or no change in either direction ... don't report anything. */ + + goto ignored; + } + + /* When we see a big difference, snap to the new x/y thresholds */ + + priv->threshx = x; + priv->threshy = y; + + /* Update the x/y position in the sample data */ + + priv->sample.x = priv->threshx; + priv->sample.y = priv->threshy; /* The X/Y positional data is now valid */ @@ -642,10 +688,6 @@ static void ads7843e_worker(FAR void *arg) priv->sample.contact = CONTACT_DOWN; } - - /* Continue to sample the position while the pen is down */ - - wd_start(priv->wdog, ADS7843E_WDOG_DELAY, ads7843e_wdog, 1, (uint32_t)priv); } /* Indicate the availability of new sample data for this ID */ @@ -659,13 +701,15 @@ static void ads7843e_worker(FAR void *arg) /* Exit, re-enabling ADS7843E interrupts */ -errout: +ignored: + (void)ads7843e_sendcmd(priv, ADS7843_CMD_ENABPINIRQ); config->enable(config, true); - /* Release our lock on the state structure */ + /* Release our lock on the state structure and unlock the SPI bus */ sem_post(&priv->devsem); + ads7843e_unlock(priv->spi); } /**************************************************************************** @@ -1119,7 +1163,7 @@ errout: * ****************************************************************************/ -int ads7843e_register(FAR struct spi_dev_s *dev, +int ads7843e_register(FAR struct spi_dev_s *spi, FAR struct ads7843e_config_s *config, int minor) { FAR struct ads7843e_dev_s *priv; @@ -1129,11 +1173,11 @@ int ads7843e_register(FAR struct spi_dev_s *dev, #endif int ret; - ivdbg("dev: %p minor: %d\n", dev, minor); + ivdbg("spi: %p minor: %d\n", spi, minor); /* Debug-only sanity checks */ - DEBUGASSERT(dev != NULL && config != NULL && minor >= 0 && minor < 100); + DEBUGASSERT(spi != NULL && config != NULL && minor >= 0 && minor < 100); /* Create and initialize a ADS7843E device driver instance */ @@ -1151,11 +1195,14 @@ int ads7843e_register(FAR struct spi_dev_s *dev, /* Initialize the ADS7843E device driver instance */ memset(priv, 0, sizeof(struct ads7843e_dev_s)); - priv->spi = dev; /* Save the SPI device handle */ - priv->config = config; /* Save the board configuration */ - priv->wdog = wd_create(); /* Create a watchdog timer */ - sem_init(&priv->devsem, 0, 1); /* Initialize device structure semaphore */ - sem_init(&priv->waitsem, 0, 0); /* Initialize pen event wait semaphore */ + priv->spi = spi; /* Save the SPI device handle */ + priv->config = config; /* Save the board configuration */ + priv->wdog = wd_create(); /* Create a watchdog timer */ + priv->threshx = INVALID_THRESHOLD; /* Initialize thresholding logic */ + priv->threshy = INVALID_THRESHOLD; /* Initialize thresholding logic */ + + sem_init(&priv->devsem, 0, 1); /* Initialize device structure semaphore */ + sem_init(&priv->waitsem, 0, 0); /* Initialize pen event wait semaphore */ /* Make sure that interrupts are disabled */ @@ -1171,14 +1218,25 @@ int ads7843e_register(FAR struct spi_dev_s *dev, goto errout_with_priv; } + idbg("Mode: %d Bits: 8 Frequency: %d\n", + CONFIG_ADS7843E_SPIMODE, CONFIG_ADS7843E_FREQUENCY); + + /* Lock the SPI bus so that we have exclusive access */ + + ads7843e_lock(spi); + /* Configure the SPI interface */ - ads7843e_configspi(dev); + ads7843e_configspi(spi); /* Enable the PEN IRQ */ ads7843e_sendcmd(priv, ADS7843_CMD_ENABPINIRQ); + /* Unlock the bus */ + + ads7843e_unlock(spi); + /* Register the device as an input device */ (void)snprintf(devname, DEV_NAMELEN, DEV_FORMAT, minor); diff --git a/nuttx/drivers/input/ads7843e.h b/nuttx/drivers/input/ads7843e.h index 43b79c7b7..6fd70d98b 100644 --- a/nuttx/drivers/input/ads7843e.h +++ b/nuttx/drivers/input/ads7843e.h @@ -139,6 +139,8 @@ struct ads7843e_dev_s uint8_t nwaiters; /* Number of threads waiting for ADS7843E data */ uint8_t id; /* Current touch point ID */ volatile bool penchange; /* An unreported event is buffered */ + uint16_t threshx; /* Thresholding X value */ + uint16_t threshy; /* Thresholding Y value */ sem_t devsem; /* Manages exclusive access to this structure */ sem_t waitsem; /* Used to wait for the availability of data */ diff --git a/nuttx/include/nuttx/input/ads7843e.h b/nuttx/include/nuttx/input/ads7843e.h index 53aa2f227..fe4382f2f 100644 --- a/nuttx/include/nuttx/input/ads7843e.h +++ b/nuttx/include/nuttx/input/ads7843e.h @@ -70,6 +70,16 @@ # define CONFIG_ADS7843E_SPIMODE SPIDEV_MODE0 #endif +/* Thresholds */ + +#ifndef CONFIG_ADS7843E_THRESHX +# define CONFIG_ADS7843E_THRESHX 12 +#endif + +#ifndef CONFIG_ADS7843E_THRESHY +# define CONFIG_ADS7843E_THRESHY 12 +#endif + /* Check for some required settings. This can save the user a lot of time * in getting the right configuration. */ @@ -149,7 +159,7 @@ extern "C" { * number * * Input Parameters: - * dev - An SPI driver instance + * spi - An SPI driver instance * config - Persistent board configuration data * minor - The input device minor number * @@ -159,7 +169,7 @@ extern "C" { * ****************************************************************************/ -EXTERN int ads7843e_register(FAR struct spi_dev_s *dev, +EXTERN int ads7843e_register(FAR struct spi_dev_s *spi, FAR struct ads7843e_config_s *config, int minor); diff --git a/nuttx/include/nuttx/input/stmpe811.h b/nuttx/include/nuttx/input/stmpe811.h index cea54a34f..fc311f7c4 100644 --- a/nuttx/include/nuttx/input/stmpe811.h +++ b/nuttx/include/nuttx/input/stmpe811.h @@ -85,7 +85,7 @@ * CONFIG_STMPE811_TEMP_DISABLE * Disable driver temperature sensor functionality. * CONFIG_STMPE811_REGDEBUG - * Enabled very low register-level debug output. Requires CONFIG_DEBUG. + * Enable very low register-level debug output. Requires CONFIG_DEBUG. * CONFIG_STMPE811_THRESHX and CONFIG_STMPE811_THRESHY * STMPE811 touchscreen data comes in a a very high rate. New touch positions * will only be reported when the X or Y data changes by these thresholds. diff --git a/nuttx/net/Kconfig b/nuttx/net/Kconfig index 718b28b8f..d4ea8befb 100644 --- a/nuttx/net/Kconfig +++ b/nuttx/net/Kconfig @@ -18,6 +18,9 @@ choice prompt "Board PHY Selection" depends on ARCH_HAVE_PHY default PHY_KS8721 + ---help--- + Identify the PHY on your board. This setting is not used by all Ethernet + drivers no do all Ethernet drivers support all PHYs. config PHY_KS8721 bool "Micrel KS8721 PHY" @@ -28,6 +31,9 @@ config PHY_DP83848C config PHY_LAN8720 bool "SMSC LAN8720 PHY" +config PHY_DM9161 + bool "Davicom DM9161 PHY" + endchoice config NET_NOINTS -- cgit v1.2.3 From f664e163e5b861f80a013423fbe1018a2de38ed0 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 27 Sep 2012 20:15:24 +0000 Subject: Fix STM32 SPI3 remap logic git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5200 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 3 +++ nuttx/arch/arm/src/stm32/stm32_gpio.c | 1 + nuttx/configs/shenzhou/nxwm/defconfig | 6 +++--- nuttx/configs/shenzhou/src/up_touchscreen.c | 3 --- nuttx/drivers/input/ads7843e.c | 3 +-- 5 files changed, 8 insertions(+), 8 deletions(-) (limited to 'nuttx') diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 1e667ddcf..48ebddfca 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3435,3 +3435,6 @@ DM9161 PHY. If the DM9161 failed to initialize, then use the up_sysemreset() logic to reset the MCU. Contributed by Darcy Gong. + * arch/arm/src/stm32/stm32_gpio.c: Add missing logic to set bit + for SPI3 remap. This fixes the XPT2046 touchscreen driver using + drivers/input/ads7843.c diff --git a/nuttx/arch/arm/src/stm32/stm32_gpio.c b/nuttx/arch/arm/src/stm32/stm32_gpio.c index 4703e8208..1dedd7ce7 100644 --- a/nuttx/arch/arm/src/stm32/stm32_gpio.c +++ b/nuttx/arch/arm/src/stm32/stm32_gpio.c @@ -128,6 +128,7 @@ static inline void stm32_gpioremap(void) val |= AFIO_MAPR_SPI1_REMAP; #endif #ifdef CONFIG_STM32_SPI3_REMAP + val |= AFIO_MAPR_SPI3_REMAP; #endif #ifdef CONFIG_STM32_I2C1_REMAP diff --git a/nuttx/configs/shenzhou/nxwm/defconfig b/nuttx/configs/shenzhou/nxwm/defconfig index b529907c1..811ba0266 100644 --- a/nuttx/configs/shenzhou/nxwm/defconfig +++ b/nuttx/configs/shenzhou/nxwm/defconfig @@ -362,9 +362,9 @@ CONFIG_INPUT_ADS7843E=y # CONFIG_ADS7843E_MULTIPLE is not set CONFIG_ADS7843E_SPIMODE=0 CONFIG_ADS7843E_FREQUENCY=100000 -# CONFIG_ADS7843E_SWAPXY is not set -CONFIG_ADS7843E_THRESHX=12 -CONFIG_ADS7843E_THRESHY=12 +CONFIG_ADS7843E_SWAPXY=y +CONFIG_ADS7843E_THRESHX=39 +CONFIG_ADS7843E_THRESHY=51 # CONFIG_INPUT_STMPE811 is not set CONFIG_LCD=y # CONFIG_LCD_NOGETRUN is not set diff --git a/nuttx/configs/shenzhou/src/up_touchscreen.c b/nuttx/configs/shenzhou/src/up_touchscreen.c index 969b23be4..4740f60a5 100644 --- a/nuttx/configs/shenzhou/src/up_touchscreen.c +++ b/nuttx/configs/shenzhou/src/up_touchscreen.c @@ -209,9 +209,6 @@ static bool tsc_busy(FAR struct ads7843e_config_s *state) * between sending the command, then reading the returned data. */ -#if 0 - up_udelay(1600); /* 1.6MS */ -#endif return false; } diff --git a/nuttx/drivers/input/ads7843e.c b/nuttx/drivers/input/ads7843e.c index ce45e4537..27060bd07 100644 --- a/nuttx/drivers/input/ads7843e.c +++ b/nuttx/drivers/input/ads7843e.c @@ -951,8 +951,7 @@ static ssize_t ads7843e_read(FAR struct file *filep, FAR char *buffer, size_t le if (sample.valid) { - report->point[0].flags = TOUCH_UP | TOUCH_ID_VALID | - TOUCH_POS_VALID | TOUCH_PRESSURE_VALID; + report->point[0].flags = TOUCH_UP | TOUCH_ID_VALID | TOUCH_POS_VALID; } else { -- cgit v1.2.3 From 8e47dd37d61f50a3c1ef985a93db0180b2688e1c Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 27 Sep 2012 20:55:15 +0000 Subject: Fix ID tagging in ADS7843/XPT2046 touchscreen driver git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5201 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/drivers/input/ads7843e.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) (limited to 'nuttx') diff --git a/nuttx/drivers/input/ads7843e.c b/nuttx/drivers/input/ads7843e.c index 27060bd07..06969e6d2 100644 --- a/nuttx/drivers/input/ads7843e.c +++ b/nuttx/drivers/input/ads7843e.c @@ -936,7 +936,7 @@ static ssize_t ads7843e_read(FAR struct file *filep, FAR char *buffer, size_t le report = (FAR struct touch_sample_s *)buffer; memset(report, 0, SIZEOF_TOUCH_SAMPLE_S(1)); report->npoints = 1; - report->point[0].id = priv->id; + report->point[0].id = sample.id; report->point[0].x = sample.x; report->point[0].y = sample.y; -- cgit v1.2.3 From 343817a6fd4a9d7f7ea393071ad2e0935162bdec Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 28 Sep 2012 19:24:46 +0000 Subject: Turn off LCD reading on Shenzhou board (needs some TLC before it will be usable) git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5202 42af7a65-404d-4744-a932-0658087f49c3 --- NxWidgets/ChangeLog.txt | 2 + NxWidgets/Kconfig | 11 +++- apps/ChangeLog.txt | 2 + apps/NxWidgets/Kconfig | 11 +++- nuttx/ChangeLog | 8 +++ nuttx/configs/shenzhou/README.txt | 42 +++++++++---- nuttx/configs/shenzhou/nxwm/defconfig | 6 +- nuttx/configs/shenzhou/src/up_ssd1289.c | 10 ++-- nuttx/drivers/lcd/ssd1289.c | 103 ++++++++++++++++++++++++++++---- 9 files changed, 159 insertions(+), 36 deletions(-) (limited to 'nuttx') diff --git a/NxWidgets/ChangeLog.txt b/NxWidgets/ChangeLog.txt index 840c0640b..03b416001 100644 --- a/NxWidgets/ChangeLog.txt +++ b/NxWidgets/ChangeLog.txt @@ -168,3 +168,5 @@ exactly sure how to do that. * libnxwidgets/Makefile and NxWidgets/nxwm/Makefile: Need updates for consistency with recent changes to NuttX build system (>= 6.22) +* Kconfig: Add option to turn on the memory monitor feature of the + NxWidgets/NxWM unit tests. diff --git a/NxWidgets/Kconfig b/NxWidgets/Kconfig index 1d7852507..6befd1ace 100644 --- a/NxWidgets/Kconfig +++ b/NxWidgets/Kconfig @@ -3,7 +3,7 @@ # see misc/tools/kconfig-language.txt. # -menuconfig NXWIDGETS +config NXWIDGETS bool "Enable NxWidgets" default n depends on NX && HAVE_CXX @@ -201,9 +201,16 @@ config NXWIDGETS_CURSORCONTROL_SIZE of cursor controls that can between entered by NX polling cycles without losing data. Default: 4 +config NXWIDGET_MEMMONITOR + bool "Memory Usage Monitor" + default n + ---help--- + Enable memory usage monitor instrumentation. This feature is only + used by the NxWidget/NxWM unit tests. + endif -menuconfig NXWM +config NXWM bool "Enable NxWM" default n depends on NXWIDGETS && NX_MULTIUSER diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index 64a923559..a14f51323 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -346,3 +346,5 @@ possible to configure NxWidgets/NxWM without too much trouble (with the tradeoff being a kind ugly structure and some maintenance issues). * apps/examples/Make.defs: Missing support for apps/examples/watchdog. + * apps/NxWidgets/Kconfig: Add option to turn on the memory monitor + feature of the NxWidgets/NxWM unit tests. diff --git a/apps/NxWidgets/Kconfig b/apps/NxWidgets/Kconfig index 1d7852507..6befd1ace 100644 --- a/apps/NxWidgets/Kconfig +++ b/apps/NxWidgets/Kconfig @@ -3,7 +3,7 @@ # see misc/tools/kconfig-language.txt. # -menuconfig NXWIDGETS +config NXWIDGETS bool "Enable NxWidgets" default n depends on NX && HAVE_CXX @@ -201,9 +201,16 @@ config NXWIDGETS_CURSORCONTROL_SIZE of cursor controls that can between entered by NX polling cycles without losing data. Default: 4 +config NXWIDGET_MEMMONITOR + bool "Memory Usage Monitor" + default n + ---help--- + Enable memory usage monitor instrumentation. This feature is only + used by the NxWidget/NxWM unit tests. + endif -menuconfig NXWM +config NXWM bool "Enable NxWM" default n depends on NXWIDGETS && NX_MULTIUSER diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 48ebddfca..70c31dcee 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3438,3 +3438,11 @@ * arch/arm/src/stm32/stm32_gpio.c: Add missing logic to set bit for SPI3 remap. This fixes the XPT2046 touchscreen driver using drivers/input/ads7843.c + * configs/shenzhou/src/up_ssd1289.c: Fix naming error in + conditional compilation. + * configs/shenzhou/nxwm/defconfig: Disable reading from the LCD. + This does not work. The hardware and the driver support the + capability, but there is some bug that causes memory corruption. + The work around for now: Just disable reading from the LCD. + * drivers/lcd/ssd1289.c: Add some logic to reduce the amount of + output when CONFIG_DEBUG_LCD is enabled. diff --git a/nuttx/configs/shenzhou/README.txt b/nuttx/configs/shenzhou/README.txt index 9c358c5a5..515b487e7 100644 --- a/nuttx/configs/shenzhou/README.txt +++ b/nuttx/configs/shenzhou/README.txt @@ -702,11 +702,11 @@ Where is one of the following: This is a special configuration setup for the NxWM window manager UnitTest. The NxWM window manager can be found here: - trunk/NxWidgets/nxwm + nuttx-code/NxWidgets/nxwm The NxWM unit test can be found at: - trunk/NxWidgets/UnitTests/nxwm + nuttx-code/NxWidgets/UnitTests/nxwm NOTE: JP6 selects between the touchscreen interrupt and the MII interrupt. It should be positioned 1-2 to enable the touchscreen @@ -714,13 +714,13 @@ Where is one of the following: Documentation for installing the NxWM unit test can be found here: - trunk/NxWidgets/UnitTests/README.txt + nuttx-code/NxWidgets/UnitTests/README.txt Here is the quick summary of the build steps: 1. Intall the nxwm configuration - $ cd ~/nuttx/trunk/nuttx/tools + $ cd ~/nuttx/nuttx-code/tools $ ./configure.sh shenzhou/nxwm 2. Make the build context (only) @@ -732,25 +732,41 @@ Where is one of the following: 3. Install the nxwm unit test - $ cd ~/nuttx/trunk/NxWidgets - $ tools/install.sh ~/nuttx/trunk/apps nxwm + $ cd ~/nuttx/nuttx-code/NxWidgets + $ tools/install.sh ~/nuttx/nuttx-code/apps nxwm Creating symbolic link - - To ~/nuttx/trunk/NxWidgets/UnitTests/nxwm - - At ~/nuttx/trunk/apps/external + - To ~/nuttx/nuttx-code/NxWidgets/UnitTests/nxwm + - At ~/nuttx/nuttx-code/apps/external 4. Build the NxWidgets library - $ cd ~/nuttx/trunk/NxWidgets/libnxwidgets - $ make TOPDIR=~/nuttx/trunk/nuttx + $ cd ~/nuttx/nuttx-code/NxWidgets/libnxwidgets + $ make TOPDIR=~/nuttx/nuttx-code ... 5. Build the NxWM library - $ cd ~/nuttx/trunk/NxWidgets/nxwm - $ make TOPDIR=~//nuttx/trunk/nuttx + $ cd ~/nuttx/nuttx-code/NxWidgets/nxwm + $ make TOPDIR=~/nuttx/nuttx-code ... 6. Built NuttX with the installed unit test as the application - $ cd ~/nuttx/trunk/nuttx + $ cd ~/nuttx/nuttx-code $ make + + NOTE: Reading from the LCD is not currently supported by this + configuration. The hardware will support reading from the LCD + and drivers/lcd/ssd1289.c also supports reading from the LCD. + This limits some graphics capabilities. + + If you enable reading from the LCD, you will see some memory + corruption. If you get inspired to debug this problem, you can + turn the LCD read functionality back on by setting: + + -CONFIG_LCD_NOGETRUN=y + +# CONFIG_LCD_NOGETRUN is not set + + -CONFIG_NX_WRITEONLY=y + +# CONFIG_NX_WRITEONLY is not set + \ No newline at end of file diff --git a/nuttx/configs/shenzhou/nxwm/defconfig b/nuttx/configs/shenzhou/nxwm/defconfig index 811ba0266..4b84144b6 100644 --- a/nuttx/configs/shenzhou/nxwm/defconfig +++ b/nuttx/configs/shenzhou/nxwm/defconfig @@ -197,7 +197,6 @@ CONFIG_STM32_PHYSR_100FD=0x8000 CONFIG_STM32_RMII=y CONFIG_STM32_RMII_MCO=y # CONFIG_STM32_RMII_EXTCLK is not set -# CONFIG_STM32_ETHMAC_REGDEBUG is not set # # USB Host Configuration @@ -367,7 +366,7 @@ CONFIG_ADS7843E_THRESHX=39 CONFIG_ADS7843E_THRESHY=51 # CONFIG_INPUT_STMPE811 is not set CONFIG_LCD=y -# CONFIG_LCD_NOGETRUN is not set +CONFIG_LCD_NOGETRUN=y CONFIG_LCD_MAXCONTRAST=1 CONFIG_LCD_MAXPOWER=1 # CONFIG_LCD_P14201 is not set @@ -487,7 +486,7 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_NX=y CONFIG_NX_LCDDRIVER=y CONFIG_NX_NPLANES=1 -# CONFIG_NX_WRITEONLY is not set +CONFIG_NX_WRITEONLY=y # # Supported Pixel Depths @@ -1075,6 +1074,7 @@ CONFIG_NXWIDGETS_CONTINUE_REPEAT_TIME=200 CONFIG_NXWIDGETS_DOUBLECLICK_TIME=350 CONFIG_NXWIDGETS_KBDBUFFER_SIZE=16 CONFIG_NXWIDGETS_CURSORCONTROL_SIZE=4 +# CONFIG_NXWIDGET_MEMMONITOR is not set CONFIG_NXWM=y # diff --git a/nuttx/configs/shenzhou/src/up_ssd1289.c b/nuttx/configs/shenzhou/src/up_ssd1289.c index 00e0ac0dd..50a99bddf 100644 --- a/nuttx/configs/shenzhou/src/up_ssd1289.c +++ b/nuttx/configs/shenzhou/src/up_ssd1289.c @@ -122,7 +122,7 @@ static void stm32_lcdshow(FAR struct stm32_lower_s *priv, FAR const char *msg); #endif static void stm32_wrdata(FAR struct stm32_lower_s *priv, uint16_t data); -#ifndef CONFIG_SSD1289_WRONLY +#ifndef CONFIG_LCD_NOGETRUN static inline uint16_t stm32_rddata(FAR struct stm32_lower_s *priv); #endif @@ -131,7 +131,7 @@ static inline uint16_t stm32_rddata(FAR struct stm32_lower_s *priv); static void stm32_select(FAR struct ssd1289_lcd_s *dev); static void stm32_deselect(FAR struct ssd1289_lcd_s *dev); static void stm32_index(FAR struct ssd1289_lcd_s *dev, uint8_t index); -#ifndef CONFIG_SSD1289_WRONLY +#ifndef CONFIG_LCD_NOGETRUN static uint16_t stm32_read(FAR struct ssd1289_lcd_s *dev); #endif static void stm32_write(FAR struct ssd1289_lcd_s *dev, uint16_t data); @@ -253,7 +253,7 @@ static struct stm32_lower_s g_lcdlower = .select = stm32_select, .deselect = stm32_deselect, .index = stm32_index, -#ifndef CONFIG_SSD1289_WRONLY +#ifndef CONFIG_LCD_NOGETRUN .read = stm32_read, #endif .write = stm32_write, @@ -326,7 +326,7 @@ static void stm32_wrdata(FAR struct stm32_lower_s *priv, uint16_t data) * ************************************************************************************/ -#ifndef CONFIG_SSD1289_WRONLY +#ifndef CONFIG_LCD_NOGETRUN static inline uint16_t stm32_rddata(FAR struct stm32_lower_s *priv) { uint16_t regval; @@ -407,7 +407,7 @@ static void stm32_index(FAR struct ssd1289_lcd_s *dev, uint8_t index) * ************************************************************************************/ -#ifndef CONFIG_SSD1289_WRONLY +#ifndef CONFIG_LCD_NOGETRUN static uint16_t stm32_read(FAR struct ssd1289_lcd_s *dev) { FAR struct stm32_lower_s *priv = (FAR struct stm32_lower_s *)dev; diff --git a/nuttx/drivers/lcd/ssd1289.c b/nuttx/drivers/lcd/ssd1289.c index f5f11b87d..e42b5bded 100644 --- a/nuttx/drivers/lcd/ssd1289.c +++ b/nuttx/drivers/lcd/ssd1289.c @@ -229,8 +229,8 @@ /* Debug ******************************************************************************/ #ifdef CONFIG_DEBUG_LCD -# define lcddbg dbg -# define lcdvdbg vdbg +# define lcddbg dbg +# define lcdvdbg vdbg #else # define lcddbg(x...) # define lcdvdbg(x...) @@ -253,6 +253,16 @@ struct ssd1289_dev_s FAR struct ssd1289_lcd_s *lcd; /* The contained platform-specific, LCD interface */ uint8_t power; /* Current power setting */ + /* These fields simplify and reduce debug output */ + +#ifdef CONFIG_DEBUG_LCD + bool put; /* Last raster operation was a putrun */ + fb_coord_t firstrow; /* First row of the run */ + fb_coord_t lastrow; /* Last row of the run */ + fb_coord_t col; /* Column of the run */ + size_t npixels; /* Length of the run */ +#endif + /* This is working memory allocated by the LCD driver for each LCD device * and for each color plane. This memory will hold one raster line of data. * The size of the allocated run buffer must therefore be at least @@ -287,6 +297,19 @@ static void ssd1289_setcursor(FAR struct ssd1289_lcd_s *lcd, uint16_t column, /* LCD Data Transfer Methods */ +#if 0 /* Sometimes useful */ +static void ssd1289_dumprun(FAR const char *msg, FAR uint16_t *run, size_t npixels); +#else +# define ssd1289_dumprun(m,r,n) +#endif + +#ifdef CONFIG_DEBUG_LCD +static void ssd1289_showrun(FAR struct ssd1289_dev_s *priv, fb_coord_t row, + fb_coord_t col, size_t npixels, bool put); +#else +# define ssd1289_showrun(p,r,c,n,b) +#endif + static int ssd1289_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buffer, size_t npixels); static int ssd1289_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer, @@ -488,6 +511,64 @@ static void ssd1289_dumprun(FAR const char *msg, FAR uint16_t *run, size_t npixe } #endif +/************************************************************************************** + * Name: ssd1289_showrun + * + * Description: + * When LCD debug is enabled, try to reduce then amount of ouptut data generated by + * ssd1289_putrun and ssd1289_getrun + * + **************************************************************************************/ + +#ifdef CONFIG_DEBUG_LCD +static void ssd1289_showrun(FAR struct ssd1289_dev_s *priv, fb_coord_t row, + fb_coord_t col, size_t npixels, bool put) +{ + fb_coord_t nextrow = priv->lastrow + 1; + + /* Has anything changed (other than the row is the next row in the sequence)? */ + + if (put == priv->put && row == nextrow && col == priv->col && + npixels == priv->npixels) + { + /* No, just update the last row */ + + priv->lastrow = nextrow; + } + else + { + /* Yes... then this is the end of the preceding sequence. Output the last run + * (if there were more than one run in the sequence). + */ + + if (priv->firstrow != priv->lastrow) + { + lcddbg("...\n"); + lcddbg("%s row: %d col: %d npixels: %d\n", + priv->put ? "PUT" : "GET", + priv->lastrow, priv->col, priv->npixels); + } + + /* And we are starting a new sequence. Output the first run of the + * new sequence + */ + + lcddbg("%s row: %d col: %d npixels: %d\n", + put ? "PUT" : "GET", row, col, npixels); + + /* And save information about the run so that we can detect continuations + * of the sequence. + */ + + priv->put = put; + priv->firstrow = row; + priv->lastrow = row; + priv->col = col; + priv->npixels = npixels; + } +} +#endif + /************************************************************************************** * Name: ssd1289_putrun * @@ -512,7 +593,7 @@ static int ssd1289_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buf /* Buffer must be provided and aligned to a 16-bit address boundary */ - lcdvdbg("row: %d col: %d npixels: %d\n", row, col, npixels); + ssd1289_showrun(priv, row, col, npixels, true); DEBUGASSERT(buffer && ((uintptr_t)buffer & 1) == 0); /* Select the LCD */ @@ -536,7 +617,7 @@ static int ssd1289_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buf ssd1289_gramselect(lcd); ssd1289_gramwrite(lcd, *src); - /* Increment to next column */ + /* Increment to the next column */ src++; col++; @@ -581,7 +662,7 @@ static int ssd1289_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buf ssd1289_gramselect(lcd); ssd1289_gramwrite(lcd, *src); - /* Increment to next column */ + /* Increment to the next column */ src++; col--; @@ -604,7 +685,7 @@ static int ssd1289_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buf ssd1289_gramselect(lcd); ssd1289_gramwrite(lcd, *src); - /* Decrement to next column */ + /* Decrement to the next column */ src++; col++; @@ -632,7 +713,7 @@ static int ssd1289_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buf **************************************************************************************/ static int ssd1289_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer, - size_t npixels) + size_t npixels) { #ifndef CONFIG_LCD_NOGETRUN FAR struct ssd1289_dev_s *priv = &g_lcddev; @@ -643,7 +724,7 @@ static int ssd1289_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer, /* Buffer must be provided and aligned to a 16-bit address boundary */ - lcdvdbg("row: %d col: %d npixels: %d\n", row, col, npixels); + ssd1289_showrun(priv, row, col, npixels, false); DEBUGASSERT(buffer && ((uintptr_t)buffer & 1) == 0); /* Select the LCD */ @@ -666,7 +747,7 @@ static int ssd1289_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer, ssd1289_readsetup(lcd, &accum); *dest++ = ssd1289_gramread(lcd, &accum); - /* Increment to next column */ + /* Increment to the next column */ col++; } @@ -715,7 +796,7 @@ static int ssd1289_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer, ssd1289_readsetup(lcd, &accum); *dest++ = ssd1289_gramread(lcd, &accum); - /* Increment to next column */ + /* Increment to the next column */ col--; } @@ -738,7 +819,7 @@ static int ssd1289_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer, ssd1289_readsetup(lcd, &accum); *dest++ = ssd1289_gramread(lcd, &accum); - /* Decrement to next column */ + /* Decrement to the next column */ col++; } -- cgit v1.2.3 From 4333422d5fb28a10118a186f8af53c903a49b7bc Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 28 Sep 2012 22:45:12 +0000 Subject: Put Shenzhou NxWM config on a diet git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5203 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 4 ++ nuttx/configs/shenzhou/README.txt | 6 +-- nuttx/configs/shenzhou/nxwm/defconfig | 81 +++++++++++------------------------ 3 files changed, 31 insertions(+), 60 deletions(-) (limited to 'nuttx') diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 70c31dcee..ed9962df0 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3446,3 +3446,7 @@ The work around for now: Just disable reading from the LCD. * drivers/lcd/ssd1289.c: Add some logic to reduce the amount of output when CONFIG_DEBUG_LCD is enabled. + * configs/shenzhou/nxwm/defconfig: Bug found and fixed... The + original configuration had too much stuff turned on. Reducing + stack sizes, some features, and buffer sizes made the + configuration reliable (Reading from the LCD is still disabled). diff --git a/nuttx/configs/shenzhou/README.txt b/nuttx/configs/shenzhou/README.txt index 515b487e7..fcc39de74 100644 --- a/nuttx/configs/shenzhou/README.txt +++ b/nuttx/configs/shenzhou/README.txt @@ -760,9 +760,9 @@ Where is one of the following: and drivers/lcd/ssd1289.c also supports reading from the LCD. This limits some graphics capabilities. - If you enable reading from the LCD, you will see some memory - corruption. If you get inspired to debug this problem, you can - turn the LCD read functionality back on by setting: + Reading from the LCD is not supported only because it has not + been test. If you get inspired to test this feature, you can + turn the LCD read functionality on by setting: -CONFIG_LCD_NOGETRUN=y +# CONFIG_LCD_NOGETRUN is not set diff --git a/nuttx/configs/shenzhou/nxwm/defconfig b/nuttx/configs/shenzhou/nxwm/defconfig index 4b84144b6..1b21fbd1b 100644 --- a/nuttx/configs/shenzhou/nxwm/defconfig +++ b/nuttx/configs/shenzhou/nxwm/defconfig @@ -121,15 +121,15 @@ CONFIG_STM32_CODESOURCERYW=y # CONFIG_STM32_CRC is not set # CONFIG_STM32_DMA1 is not set # CONFIG_STM32_DMA2 is not set -CONFIG_STM32_BKP=y +# CONFIG_STM32_BKP is not set # CONFIG_STM32_CAN1 is not set # CONFIG_STM32_DAC1 is not set # CONFIG_STM32_DAC2 is not set CONFIG_STM32_ETHMAC=y -CONFIG_STM32_I2C1=y +# CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_IWDG is not set -CONFIG_STM32_PWR=y +# CONFIG_STM32_PWR is not set # CONFIG_STM32_SPI1 is not set # CONFIG_STM32_SPI2 is not set CONFIG_STM32_SPI3=y @@ -149,14 +149,12 @@ CONFIG_STM32_USART2=y # CONFIG_STM32_USB is not set # CONFIG_STM32_WWDG is not set CONFIG_STM32_SPI=y -CONFIG_STM32_I2C=y # # Alternate Pin Mapping # CONFIG_STM32_USART2_REMAP=y CONFIG_STM32_SPI3_REMAP=y -# CONFIG_STM32_I2C1_REMAP is not set CONFIG_STM32_ETH_REMAP=y # CONFIG_STM32_JTAG_DISABLE is not set CONFIG_STM32_JTAG_FULL_ENABLE=y @@ -171,15 +169,6 @@ CONFIG_STM32_JTAG_FULL_ENABLE=y # CONFIG_STM32_SPI_INTERRUPTS is not set # CONFIG_STM32_SPI_DMA is not set -# -# I2C Configuration -# -# CONFIG_STM32_I2C_DYNTIMEO is not set -CONFIG_STM32_I2CTIMEOSEC=0 -CONFIG_STM32_I2CTIMEOMS=500 -CONFIG_STM32_I2CTIMEOTICKS=500 -# CONFIG_STM32_I2C_DUTY16_9 is not set - # # Ethernet MAC configuration # @@ -285,10 +274,10 @@ CONFIG_SDCLONE_DISABLE=y CONFIG_SCHED_WORKQUEUE=y CONFIG_SCHED_WORKPRIORITY=192 CONFIG_SCHED_WORKPERIOD=50000 -CONFIG_SCHED_WORKSTACKSIZE=2048 +CONFIG_SCHED_WORKSTACKSIZE=1024 CONFIG_SIG_SIGWORK=4 # CONFIG_SCHED_LPWORK is not set -CONFIG_SCHED_WAITPID=y +# CONFIG_SCHED_WAITPID is not set # CONFIG_SCHED_ATEXIT is not set CONFIG_SCHED_ONEXIT=y CONFIG_SCHED_ONEXIT_MAX=1 @@ -323,9 +312,9 @@ CONFIG_PREALLOC_TIMERS=4 # # CONFIG_CUSTOM_STACK is not set CONFIG_IDLETHREAD_STACKSIZE=1024 -CONFIG_USERMAIN_STACKSIZE=2048 +CONFIG_USERMAIN_STACKSIZE=1024 CONFIG_PTHREAD_STACK_MIN=256 -CONFIG_PTHREAD_STACK_DEFAULT=2048 +CONFIG_PTHREAD_STACK_DEFAULT=1024 # # Device Drivers @@ -336,22 +325,13 @@ CONFIG_DEV_NULL=y # CONFIG_RAMDISK is not set # CONFIG_CAN is not set # CONFIG_PWM is not set -CONFIG_I2C=y -# CONFIG_I2C_SLAVE is not set -CONFIG_I2C_TRANSFER=y -# CONFIG_I2C_WRITEREAD is not set -CONFIG_I2C_POLLED=y -# CONFIG_I2C_TRACE is not set +# CONFIG_I2C is not set CONFIG_ARCH_HAVE_I2CRESET=y -# CONFIG_I2C_RESET is not set CONFIG_SPI=y # CONFIG_SPI_OWNBUS is not set CONFIG_SPI_EXCHANGE=y # CONFIG_SPI_CMDDATA is not set -CONFIG_RTC=y -# CONFIG_RTC_DATETIME is not set -# CONFIG_RTC_HIRES is not set -# CONFIG_RTC_ALARM is not set +# CONFIG_RTC is not set # CONFIG_WATCHDOG is not set # CONFIG_ANALOG is not set # CONFIG_BCH is not set @@ -432,16 +412,16 @@ CONFIG_PHY_DM9161=y # CONFIG_NET_NOINTS is not set CONFIG_NET_MULTIBUFFER=y # CONFIG_NET_IPv6 is not set -CONFIG_NSOCKET_DESCRIPTORS=10 +CONFIG_NSOCKET_DESCRIPTORS=16 CONFIG_NET_NACTIVESOCKETS=16 CONFIG_NET_SOCKOPTS=y CONFIG_NET_BUFSIZE=562 # CONFIG_NET_TCPURGDATA is not set CONFIG_NET_TCP=y -CONFIG_NET_TCP_CONNS=40 -CONFIG_NET_MAX_LISTENPORTS=40 +CONFIG_NET_TCP_CONNS=16 +CONFIG_NET_MAX_LISTENPORTS=16 CONFIG_NET_TCP_READAHEAD_BUFSIZE=562 -CONFIG_NET_NTCP_READAHEAD_BUFFERS=16 +CONFIG_NET_NTCP_READAHEAD_BUFFERS=4 CONFIG_NET_TCP_RECVDELAY=0 CONFIG_NET_TCPBACKLOG=y CONFIG_NET_UDP=y @@ -464,12 +444,7 @@ CONFIG_NET_ARPTAB_SIZE=16 # # File system configuration # -CONFIG_FS_FAT=y -CONFIG_FAT_LCNAMES=y -CONFIG_FAT_LFN=y -CONFIG_FAT_MAXFNAME=32 -# CONFIG_FS_FATTIME is not set -# CONFIG_FAT_DMAMEMORY is not set +# CONFIG_FS_FAT is not set # CONFIG_FS_RAMMAP is not set # CONFIG_NFS is not set # CONFIG_FS_NXFFS is not set @@ -962,7 +937,7 @@ CONFIG_NETUTILS_WEBCLIENT=y # NSH Library # CONFIG_NSH_LIBRARY=y -CONFIG_NSH_BUILTIN_APPS=y +# CONFIG_NSH_BUILTIN_APPS is not set # # Disable Individual commands @@ -1016,9 +991,9 @@ CONFIG_NSH_ARCHINIT=y CONFIG_NSH_TELNET=y CONFIG_NSH_TELNETD_PORT=23 CONFIG_NSH_TELNETD_DAEMONPRIO=100 -CONFIG_NSH_TELNETD_DAEMONSTACKSIZE=2048 +CONFIG_NSH_TELNETD_DAEMONSTACKSIZE=1596 CONFIG_NSH_TELNETD_CLIENTPRIO=100 -CONFIG_NSH_TELNETD_CLIENTSTACKSIZE=2048 +CONFIG_NSH_TELNETD_CLIENTSTACKSIZE=1596 CONFIG_NSH_IOBUFFER_SIZE=512 CONFIG_NSH_IPADDR=0x0a000002 CONFIG_NSH_DRIPADDR=0x0a000001 @@ -1036,10 +1011,10 @@ CONFIG_NXWIDGETS=y CONFIG_NXWIDGETS_DEVNO=0 CONFIG_NXWIDGETS_VPLANE=0 CONFIG_NXWIDGETS_SERVERPRIO=51 -CONFIG_NXWIDGETS_SERVERSTACK=2048 +CONFIG_NXWIDGETS_SERVERSTACK=1596 CONFIG_NXWIDGETS_CLIENTPRIO=50 CONFIG_NXWIDGETS_LISTENERPRIO=50 -CONFIG_NXWIDGETS_LISTENERSTACK=2048 +CONFIG_NXWIDGETS_LISTENERSTACK=1596 # CONFIG_NXWIDGETS_EXTERNINIT is not set # CONFIG_NXWIDGET_EVENTWAIT is not set @@ -1128,13 +1103,13 @@ CONFIG_NXWM_STARTWINDOW_MQNAME="/dev/nxwm" CONFIG_NXWM_STARTWINDOW_MXMSGS=32 CONFIG_NXWM_STARTWINDOW_MXMPRIO=42 CONFIG_NXWM_STARTWINDOW_PRIO=50 -CONFIG_NXWM_STARTWINDOW_STACKSIZE=2048 +CONFIG_NXWM_STARTWINDOW_STACKSIZE=1596 # # NxConsole Window Configuration # CONFIG_NXWM_NXCONSOLE_PRIO=50 -CONFIG_NXWM_NXCONSOLE_STACKSIZE=2048 +CONFIG_NXWM_NXCONSOLE_STACKSIZE=1596 CONFIG_NXWM_NXCONSOLE_WCOLOR= CONFIG_NXWM_NXCONSOLE_FONTCOLOR= CONFIG_NXWM_NXCONSOLE_FONTID= @@ -1148,7 +1123,7 @@ CONFIG_NXWM_TOUCHSCREEN_DEVNO=0 CONFIG_NXWM_TOUCHSCREEN_DEVPATH="/dev/input0" CONFIG_NXWM_TOUCHSCREEN_SIGNO=5 CONFIG_NXWM_TOUCHSCREEN_LISTENERPRIO=50 -CONFIG_NXWM_TOUCHSCREEN_LISTENERSTACK= +CONFIG_NXWM_TOUCHSCREEN_LISTENERSTACK=1596 CONFIG_NXWM_KEYBOARD=y # @@ -1158,7 +1133,7 @@ CONFIG_NXWM_KEYBOARD_DEVPATH="/dev/console" CONFIG_NXWM_KEYBOARD_SIGNO=6 CONFIG_NXWM_KEYBOARD_BUFSIZE=16 CONFIG_NXWM_KEYBOARD_LISTENERPRIO=50 -CONFIG_NXWM_KEYBOARD_LISTENERSTACK=2048 +CONFIG_NXWM_KEYBOARD_LISTENERSTACK=1024 # # Calibration display settings @@ -1170,7 +1145,7 @@ CONFIG_NXWM_CALIBRATION_TOUCHEDCOLOR= CONFIG_NXWM_CALIBRATION_ICON="" CONFIG_NXWM_CALIBRATION_SIGNO=5 CONFIG_NXWM_CALIBRATION_LISTENERPRIO=50 -CONFIG_NXWM_CALIBRATION_LISTENERSTACK=2048 +CONFIG_NXWM_CALIBRATION_LISTENERSTACK=1024 # # Calibration display settings @@ -1191,14 +1166,6 @@ CONFIG_NXWM_HEXCALCULATOR_FONTID=5 # # I2C tool # -CONFIG_SYSTEM_I2CTOOL=y -CONFIG_I2CTOOL_BUILTIN=y -CONFIG_I2CTOOL_MINBUS=1 -CONFIG_I2CTOOL_MAXBUS=3 -CONFIG_I2CTOOL_MINADDR=0x03 -CONFIG_I2CTOOL_MAXADDR=0x77 -CONFIG_I2CTOOL_MAXREGADDR=0xff -CONFIG_I2CTOOL_DEFFREQ=100000 # # FLASH Program Installation -- cgit v1.2.3 From ccb682f332e5ad1d9cdfd97a9a3ee12e6d00b898 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 29 Sep 2012 14:13:04 +0000 Subject: Fix problem with ping that prevent ping from going outside local network (Darcy Gong) git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5204 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 3 + nuttx/configs/shenzhou/README.txt | 23 +++-- nuttx/configs/sim/README.txt | 6 +- nuttx/configs/stm3220g-eval/README.txt | 29 +++--- nuttx/configs/stm3220g-eval/nxwm/defconfig | 14 ++- nuttx/configs/stm3240g-eval/README.txt | 29 +++--- nuttx/net/uip/uip_icmpping.c | 157 +++++++++++++++-------------- 7 files changed, 143 insertions(+), 118 deletions(-) (limited to 'nuttx') diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index ed9962df0..526c8a335 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3450,3 +3450,6 @@ original configuration had too much stuff turned on. Reducing stack sizes, some features, and buffer sizes made the configuration reliable (Reading from the LCD is still disabled). + * net/uip/uip_icmpping.c: Fix problem that prevented ping from + going outside of local network. Submitted by Darcy Gong + diff --git a/nuttx/configs/shenzhou/README.txt b/nuttx/configs/shenzhou/README.txt index fcc39de74..1f3f254aa 100644 --- a/nuttx/configs/shenzhou/README.txt +++ b/nuttx/configs/shenzhou/README.txt @@ -716,11 +716,12 @@ Where is one of the following: nuttx-code/NxWidgets/UnitTests/README.txt - Here is the quick summary of the build steps: + Here is the quick summary of the build steps (Assuming that all of + the required packages are available in a directory ~/nuttx-code): 1. Intall the nxwm configuration - $ cd ~/nuttx/nuttx-code/tools + $ cd ~/nuttx-code/tools $ ./configure.sh shenzhou/nxwm 2. Make the build context (only) @@ -732,27 +733,27 @@ Where is one of the following: 3. Install the nxwm unit test - $ cd ~/nuttx/nuttx-code/NxWidgets - $ tools/install.sh ~/nuttx/nuttx-code/apps nxwm + $ cd ~/nuttx-code/NxWidgets + $ tools/install.sh ~/nuttx-code/apps nxwm Creating symbolic link - - To ~/nuttx/nuttx-code/NxWidgets/UnitTests/nxwm - - At ~/nuttx/nuttx-code/apps/external + - To ~/nuttx-code/NxWidgets/UnitTests/nxwm + - At ~/nuttx-code/apps/external 4. Build the NxWidgets library - $ cd ~/nuttx/nuttx-code/NxWidgets/libnxwidgets - $ make TOPDIR=~/nuttx/nuttx-code + $ cd ~/nuttx-code/NxWidgets/libnxwidgets + $ make TOPDIR=~/nuttx-code ... 5. Build the NxWM library - $ cd ~/nuttx/nuttx-code/NxWidgets/nxwm - $ make TOPDIR=~/nuttx/nuttx-code + $ cd ~/nuttx-code/NxWidgets/nxwm + $ make TOPDIR=~/nuttx-code ... 6. Built NuttX with the installed unit test as the application - $ cd ~/nuttx/nuttx-code + $ cd ~/nuttx-code $ make NOTE: Reading from the LCD is not currently supported by this diff --git a/nuttx/configs/sim/README.txt b/nuttx/configs/sim/README.txt index 833ec58dc..b8a921e7f 100644 --- a/nuttx/configs/sim/README.txt +++ b/nuttx/configs/sim/README.txt @@ -409,15 +409,15 @@ nxwm This is a special configuration setup for the NxWM window manager UnitTest. The NxWM window manager can be found here: - trunk/NxWidgets/nxwm + nuttx-code/NxWidgets/nxwm The NxWM unit test can be found at: - trunk/NxWidgets/UnitTests/nxwm + nuttx-code/NxWidgets/UnitTests/nxwm Documentation for installing the NxWM unit test can be found here: - trunk/NxWidgets/UnitTests/READEM.txt + nuttx-code/NxWidgets/UnitTests/READEM.txt NOTE: There is an issue with running this example under the simulation. In the default configuration, this example will diff --git a/nuttx/configs/stm3220g-eval/README.txt b/nuttx/configs/stm3220g-eval/README.txt index b3b7fd476..89c6b9233 100644 --- a/nuttx/configs/stm3220g-eval/README.txt +++ b/nuttx/configs/stm3220g-eval/README.txt @@ -947,21 +947,22 @@ Where is one of the following: This is a special configuration setup for the NxWM window manager UnitTest. The NxWM window manager can be found here: - trunk/NxWidgets/nxwm + nuttx-code/NxWidgets/nxwm The NxWM unit test can be found at: - trunk/NxWidgets/UnitTests/nxwm + nuttx-code/NxWidgets/UnitTests/nxwm Documentation for installing the NxWM unit test can be found here: - trunk/NxWidgets/UnitTests/README.txt + nuttx-code/NxWidgets/UnitTests/README.txt - Here is the quick summary of the build steps: + Here is the quick summary of the build steps (Assuming that all of + the required packages are available in a directory ~/nuttx-code): 1. Intall the nxwm configuration - $ cd ~/nuttx/trunk/nuttx/tools + $ cd ~/nuttx-code/nuttx/tools $ ./configure.sh stm3220g-eval/nxwm 2. Make the build context (only) @@ -973,27 +974,27 @@ Where is one of the following: 3. Install the nxwm unit test - $ cd ~/nuttx/trunk/NxWidgets - $ tools/install.sh ~/nuttx/trunk/apps nxwm + $ cd ~/nuttx-code/NxWidgets + $ tools/install.sh ~/nuttx-code/apps nxwm Creating symbolic link - - To ~/nuttx/trunk/NxWidgets/UnitTests/nxwm - - At ~/nuttx/trunk/apps/external + - To ~/nuttx-code/NxWidgets/UnitTests/nxwm + - At ~/nuttx-code/apps/external 4. Build the NxWidgets library - $ cd ~/nuttx/trunk/NxWidgets/libnxwidgets - $ make TOPDIR=~/nuttx/trunk/nuttx + $ cd ~/nuttx-code/NxWidgets/libnxwidgets + $ make TOPDIR=~/nuttx-code/nuttx ... 5. Build the NxWM library - $ cd ~/nuttx/trunk/NxWidgets/nxwm - $ make TOPDIR=~//nuttx/trunk/nuttx + $ cd ~/nuttx-code/NxWidgets/nxwm + $ make TOPDIR=~/nuttx-code/nuttx ... 6. Built NuttX with the installed unit test as the application - $ cd ~/nuttx/trunk/nuttx + $ cd ~/nuttx-code/nuttx $ make ostest: diff --git a/nuttx/configs/stm3220g-eval/nxwm/defconfig b/nuttx/configs/stm3220g-eval/nxwm/defconfig index 7b7028cf8..83c2f4841 100644 --- a/nuttx/configs/stm3220g-eval/nxwm/defconfig +++ b/nuttx/configs/stm3220g-eval/nxwm/defconfig @@ -507,7 +507,7 @@ CONFIG_STMPE811_THRESHX=39 CONFIG_STMPE811_THRESHY=51 # -# USB Device Configuration +# STM32 USB OTG FS Device Configuration # CONFIG_USBDEV=n CONFIG_USBDEV_ISOCHRONOUS=n @@ -518,6 +518,18 @@ CONFIG_USBDEV_MAXPOWER=100 CONFIG_USBDEV_TRACE=n CONFIG_USBDEV_TRACE_NRECORDS=128 +# +# STM32 USB OTG FS Host Configuration +# +CONFIG_USBHOST=n +#CONFIG_STM32_OTGFS_RXFIFO_SIZE +#CONFIG_STM32_OTGFS_NPTXFIFO_SIZE +#CONFIG_STM32_OTGFS_PTXFIFO_SIZE +#CONFIG_STM32_OTGFS_DESCSIZE +CONFIG_STM32_OTGFS_SOFINTR=n +CONFIG_STM32_USBHOST_REGDEBUG=n +CONFIG_STM32_USBHOST_PKTDUMP=n + # # USB Serial Device Configuration # diff --git a/nuttx/configs/stm3240g-eval/README.txt b/nuttx/configs/stm3240g-eval/README.txt index 75ca1ea77..df98f087d 100644 --- a/nuttx/configs/stm3240g-eval/README.txt +++ b/nuttx/configs/stm3240g-eval/README.txt @@ -1226,21 +1226,22 @@ Where is one of the following: This is a special configuration setup for the NxWM window manager UnitTest. The NxWM window manager can be found here: - trunk/NxWidgets/nxwm + nuttx-code/NxWidgets/nxwm The NxWM unit test can be found at: - trunk/NxWidgets/UnitTests/nxwm + nuttx-code/NxWidgets/UnitTests/nxwm Documentation for installing the NxWM unit test can be found here: - trunk/NxWidgets/UnitTests/README.txt + nuttx-code/NxWidgets/UnitTests/README.txt - Here is the quick summary of the build steps: + Here is the quick summary of the build steps (Assuming that all of + the required packages are available in a directory ~/nuttx-code): 1. Intall the nxwm configuration - $ cd ~/nuttx/trunk/nuttx/tools + $ cd ~/nuttx-code/nuttx/tools $ ./configure.sh stm3240g-eval/nxwm 2. Make the build context (only) @@ -1252,27 +1253,27 @@ Where is one of the following: 3. Install the nxwm unit test - $ cd ~/nuttx/trunk/NxWidgets - $ tools/install.sh ~/nuttx/trunk/apps nxwm + $ cd ~/nuttx-code/NxWidgets + $ tools/install.sh ~/nuttx-code/apps nxwm Creating symbolic link - - To ~/nuttx/trunk/NxWidgets/UnitTests/nxwm - - At ~/nuttx/trunk/apps/external + - To ~/nuttx-code/NxWidgets/UnitTests/nxwm + - At ~/nuttx-code/apps/external 4. Build the NxWidgets library - $ cd ~/nuttx/trunk/NxWidgets/libnxwidgets - $ make TOPDIR=~/nuttx/trunk/nuttx + $ cd ~/nuttx-code/NxWidgets/libnxwidgets + $ make TOPDIR=~/nuttx-code/nuttx ... 5. Build the NxWM library - $ cd ~/nuttx/trunk/NxWidgets/nxwm - $ make TOPDIR=~//nuttx/trunk/nuttx + $ cd ~/nuttx-code/NxWidgets/nxwm + $ make TOPDIR=~/nuttx-code/nuttx ... 6. Built NuttX with the installed unit test as the application - $ cd ~/nuttx/trunk/nuttx + $ cd ~/nuttx-code/nuttx $ make ostest: diff --git a/nuttx/net/uip/uip_icmpping.c b/nuttx/net/uip/uip_icmpping.c index 356187d09..e3ebf7252 100644 --- a/nuttx/net/uip/uip_icmpping.c +++ b/nuttx/net/uip/uip_icmpping.c @@ -148,122 +148,129 @@ static inline int ping_timeout(struct icmp_ping_s *pstate) ****************************************************************************/ static uint16_t ping_interrupt(struct uip_driver_s *dev, void *conn, - void *pvpriv, uint16_t flags) + void *pvpriv, uint16_t flags) { struct icmp_ping_s *pstate = (struct icmp_ping_s *)pvpriv; uint8_t *ptr; - int failcode = -ETIMEDOUT; int i; nllvdbg("flags: %04x\n", flags); if (pstate) { - /* Check if this device is on the same network as the destination device. */ - - if (!uip_ipaddr_maskcmp(pstate->png_addr, dev->d_ipaddr, dev->d_netmask)) - { - /* Destination address was not on the local network served by this - * device. If a timeout occurs, then the most likely reason is - * that the destination address is not reachable. - */ + /* Check if this is a ICMP ECHO reply. If so, return the sequence + * number to the caller. NOTE: We may not even have sent the + * requested ECHO request; this could have been the delayed ECHO + * response from a previous ping. + */ - nllvdbg("Not reachable\n"); - failcode = -ENETUNREACH; - } - else + if ((flags & UIP_ECHOREPLY) != 0 && conn != NULL) { - /* Check if this is a ICMP ECHO reply. If so, return the sequence - * number to the caller. NOTE: We may not even have sent the - * requested ECHO request; this could have been the delayed ECHO - * response from a previous ping. - */ + struct uip_icmpip_hdr *icmp = (struct uip_icmpip_hdr *)conn; + nlldbg("ECHO reply: id=%d seqno=%d\n", + ntohs(icmp->id), ntohs(icmp->seqno)); - if ((flags & UIP_ECHOREPLY) != 0 && conn != NULL) + if (ntohs(icmp->id) == pstate->png_id) { - struct uip_icmpip_hdr *icmp = (struct uip_icmpip_hdr *)conn; - nlldbg("ECHO reply: id=%d seqno=%d\n", ntohs(icmp->id), ntohs(icmp->seqno)); + /* Consume the ECHOREPLY */ - if (ntohs(icmp->id) == pstate->png_id) - { - /* Consume the ECHOREPLY */ + flags &= ~UIP_ECHOREPLY; + dev->d_len = 0; - flags &= ~UIP_ECHOREPLY; - dev->d_len = 0; + /* Return the result to the caller */ - /* Return the result to the caller */ - - pstate->png_result = OK; - pstate->png_seqno = ntohs(icmp->seqno); - goto end_wait; - } + pstate->png_result = OK; + pstate->png_seqno = ntohs(icmp->seqno); + goto end_wait; } + } - /* Check: - * If the outgoing packet is available (it may have been claimed - * by a sendto interrupt serving a different thread - * -OR- - * If the output buffer currently contains unprocessed incoming - * data. - * -OR- - * If we have alread sent the ECHO request - * - * In the first two cases, we will just have to wait for the next - * polling cycle. - */ + /* Check: + * If the outgoing packet is available (it may have been claimed + * by a sendto interrupt serving a different thread) + * -OR- + * If the output buffer currently contains unprocessed incoming + * data. + * -OR- + * If we have alread sent the ECHO request + * + * In the first two cases, we will just have to wait for the next + * polling cycle. + */ - if (dev->d_sndlen <= 0 && /* Packet available */ - (flags & UIP_NEWDATA) == 0 && /* No incoming data */ - !pstate->png_sent) /* Request not sent */ - { - struct uip_icmpip_hdr *picmp = ICMPBUF; + if (dev->d_sndlen <= 0 && /* Packet available */ + (flags & UIP_NEWDATA) == 0 && /* No incoming data */ + !pstate->png_sent) /* Request not sent */ + { + struct uip_icmpip_hdr *picmp = ICMPBUF; - /* We can send the ECHO request now. - * - * Format the ICMP ECHO request packet - */ + /* We can send the ECHO request now. + * + * Format the ICMP ECHO request packet + */ - picmp->type = ICMP_ECHO_REQUEST; - picmp->icode = 0; + picmp->type = ICMP_ECHO_REQUEST; + picmp->icode = 0; #ifndef CONFIG_NET_IPv6 - picmp->id = htons(pstate->png_id); - picmp->seqno = htons(pstate->png_seqno); + picmp->id = htons(pstate->png_id); + picmp->seqno = htons(pstate->png_seqno); #else # error "IPv6 ECHO Request not implemented" #endif - /* Add some easily verifiable data */ + /* Add some easily verifiable data */ - for (i = 0, ptr = ICMPDAT; i < pstate->png_datlen; i++) - { - *ptr++ = i; - } + for (i = 0, ptr = ICMPDAT; i < pstate->png_datlen; i++) + { + *ptr++ = i; + } - /* Send the ICMP echo request. Note that d_sndlen is set to - * the size of the ICMP payload and does not include the size - * of the ICMP header. - */ + /* Send the ICMP echo request. Note that d_sndlen is set to + * the size of the ICMP payload and does not include the size + * of the ICMP header. + */ - nlldbg("Send ECHO request: seqno=%d\n", pstate->png_seqno); + nlldbg("Send ECHO request: seqno=%d\n", pstate->png_seqno); - dev->d_sndlen = pstate->png_datlen + 4; - uip_icmpsend(dev, &pstate->png_addr); - pstate->png_sent = true; - return flags; - } + dev->d_sndlen = pstate->png_datlen + 4; + uip_icmpsend(dev, &pstate->png_addr); + pstate->png_sent = true; + return flags; } /* Check if the selected timeout has elapsed */ if (ping_timeout(pstate)) { - /* Yes.. report the timeout */ + int failcode; + + /* Check if this device is on the same network as the destination + * device. + */ + + if (!uip_ipaddr_maskcmp(pstate->png_addr, dev->d_ipaddr, dev->d_netmask)) + { + /* Destination address was not on the local network served by this + * device. If a timeout occurs, then the most likely reason is + * that the destination address is not reachable. + */ + + nlldbg("Not reachable\n"); + failcode = -ENETUNREACH; + } + else + { + nlldbg("Ping timeout\n"); + failcode = -ETIMEDOUT; + } + + /* Report the failure */ - nlldbg("Ping timeout\n"); pstate->png_result = failcode; goto end_wait; } /* Continue waiting */ } + return flags; end_wait: -- cgit v1.2.3 From de53b28fd3ae24a81513278390ba02a5417cf8ac Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 29 Sep 2012 15:58:41 +0000 Subject: Prep for NxWidgets 1.3 release git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5205 42af7a65-404d-4744-a932-0658087f49c3 --- NxWidgets/ChangeLog.txt | 4 +++- NxWidgets/ReleaseNotes.txt | 15 +++++++++++++++ apps/ChangeLog.txt | 4 +++- nuttx/ChangeLog | 3 ++- 4 files changed, 23 insertions(+), 3 deletions(-) (limited to 'nuttx') diff --git a/NxWidgets/ChangeLog.txt b/NxWidgets/ChangeLog.txt index 03b416001..06709996f 100644 --- a/NxWidgets/ChangeLog.txt +++ b/NxWidgets/ChangeLog.txt @@ -158,7 +158,7 @@ * nxwm/Makefile: Fix error that creapt in during some other recent check-ins. -1.3 2012-xx-xx Gregory Nutt +1.3 2012-09-29 Gregory Nutt * UnitTests/*/main.cxx: Change entry point name to be consistent with with entry point naming conventions introduced in NuttX @@ -170,3 +170,5 @@ for consistency with recent changes to NuttX build system (>= 6.22) * Kconfig: Add option to turn on the memory monitor feature of the NxWidgets/NxWM unit tests. + +1.4 2012-xx-xx Gregory Nutt diff --git a/NxWidgets/ReleaseNotes.txt b/NxWidgets/ReleaseNotes.txt index 96ce29e1a..7d3fb7aaa 100644 --- a/NxWidgets/ReleaseNotes.txt +++ b/NxWidgets/ReleaseNotes.txt @@ -97,3 +97,18 @@ Bugfixes: As well as other, less critical bugs (see the ChangeLog for details) +NxWidgets-1.3 +============= + +The 4th release of the NxWidgets package as made on September 29, 2012. This +release depends on NuttX-6.22 or above and should not be used with older +NuttX releases. + +There are no functional changes in this release of NxWidgets. This release +is required in order to retain compatibility with the most recent versions +of NuttX. These comptibility changes include: + +* Naming of function entry points +* Build system changes +* Changes needed for the NuttX configuration tool + diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index a14f51323..8eb96ac69 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -279,7 +279,7 @@ * apps/*/Make.defs: Numerous fixes needed to use the automated configuration (from Richard Cochran). -6.22 2012-xx-xx Gregory Nutt +6.22 2012-09-29 Gregory Nutt * apps/netutils/thttpd/thttpd_cgi.c: Missing NULL in argv[] list (contributed by Kate). @@ -348,3 +348,5 @@ * apps/examples/Make.defs: Missing support for apps/examples/watchdog. * apps/NxWidgets/Kconfig: Add option to turn on the memory monitor feature of the NxWidgets/NxWM unit tests. + +6.23 2012-xx-xx Gregory Nutt diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 526c8a335..438d89a91 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3177,7 +3177,7 @@ * arch/arm/src/stm32/stm32_otgfshost.c: This driver now appears to be functional (although more testing is necesary). -6.22 2012-xx-xx Gregory Nutt +6.22 2012-09-29 Gregory Nutt * include/semaphore.h, sched/sem_holders.c, and lib/semaphore/sem_init.c: Fix some strange (and probably wrong) list handling when @@ -3453,3 +3453,4 @@ * net/uip/uip_icmpping.c: Fix problem that prevented ping from going outside of local network. Submitted by Darcy Gong +6.23 2012-09-29 Gregory Nutt -- cgit v1.2.3 From 253d3ab52353d640f11a95a148105d04d96a1d29 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 29 Sep 2012 19:10:52 +0000 Subject: Prep for 6.22 Release git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5206 42af7a65-404d-4744-a932-0658087f49c3 --- apps/ChangeLog.txt | 4 +- nuttx/ChangeLog | 26 +- nuttx/Documentation/NuttX.html | 1057 +++++++++++++++++++++------------------- nuttx/ReleaseNotes | 104 ++++ 4 files changed, 675 insertions(+), 516 deletions(-) (limited to 'nuttx') diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index 8eb96ac69..75f02754b 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -286,7 +286,7 @@ * apps/nshlib/nsh_parse.c: CONFIG_NSH_DISABLE_WGET not CONFIG_NSH_DISABLE_GET in one location (found by Kate). * apps/examples/ostest/prioinherit.c: Limit the number of test - threds to no more than 3 of each priority. Bad things happen + threads to no more than 3 of each priority. Bad things happen when the existing logic tried to created several hundred test treads! * apps/nshlib/nsh.h: Both CONFIG_LIBC_STRERROR and CONFIG_NSH_STRERROR @@ -341,7 +341,7 @@ * apps/netutils/webserver/httpd.c: Add support for Keep-alive connections (from Kate). * apps/NxWidget/Kconfig: This is a kludge. I created this NxWidgets - directory that ONLY contains Kconfig. NxWidgets does not like in + directory that ONLY contains Kconfig. NxWidgets does not live in either the nuttx/ or the apps/ source trees. This kludge makes it possible to configure NxWidgets/NxWM without too much trouble (with the tradeoff being a kind ugly structure and some maintenance issues). diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 438d89a91..ef9e77132 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3193,7 +3193,7 @@ speed/duplex. This does not work for certain PHYs. Still some unresolved issues (also from Kate). * tools/Config.mk, Makefile, configs/*/Make.defs: Add a new Makefile - fragement to de-quoate certain strings from the Kconfig logic that + fragment to de-quote certain strings from the Kconfig logic that need to be used at path segments (Richard Cochran). * arch/arm/src/stm32/stm32_usbotghost.c: The STM32 USB host driver only works with debug turned on. The problem appears to be that with debug @@ -3201,7 +3201,7 @@ reveals a variety of errors. This check in improves NAK robustness for control transfers but does not resolve all of the issues. * configs/stm3220g-eval/*/defconfig: Calibrated delay loop. It had - never been calibrated was was way off. + never been calibrated was way off. * sched/sem_holder.c: Add logic to handler some priority inheritance cases when sem_post() is called from an interrupt handler. The logic is clearly wrong, but it is not known if this is the @@ -3212,13 +3212,13 @@ CONFIG_LIBC_STRERROR_SHORT that can be used to output shortened strings by strerror(). * arch/arm/src/stm32/stm32_usbotghost.c: Finally... the USB OTG FS - appears to handle NAKing correctly is complete. + appears to handle NAKing correctly. * configs/stm32f4discovery/*: Added and verifed support for USB OTG FS host on the STM32F4Discovery board. * configs/*/defconfig: Remove configuration documentation from config files. It is redundant, error-prone, and difficult to maintain. Configuration documentation is available in configs/README.txt for - common configurations and in configs/*/README.txt for board and MCU_ + common configurations and in configs/*/README.txt for board and MCU- specific configurations. * configs/stm3240g-eval: Add USB host support. * sched/os_bring.c, configs/*/defconfig, tools/mkconfig.c, and others: Added @@ -3226,7 +3226,7 @@ the default entry from user_start to some other symbol. Contributed by Kate. NOTE: This change does introduce a minor backward incompatibility. For example, if your application uses NSH as its start-up program, then your - code will not fail because it will be unable to find "user_start". The fix + build will now fail because it will be unable to find "user_start". The fix for this link failure is to add the following to your configuration file: CONFIG_USER_ENTRYPOINT="nsh_main". * libs/stdio/lib_libfread.c and lib_*flush*.c: Correct a couple of @@ -3269,7 +3269,7 @@ CONFIG_HEAP2_SIZE (decimal) instead of CONFIG_HEAP2_END (hex). * tools/configure.sh: Don't append the apps directory path setting if the correct setting is already in defined in the defconfig file. - * fs/fat/fs_utils.c: Improper constructed bool expression. This + * fs/fat/fs_utils.c: Improperly constructed bool expression. This would cause many unnecessary writes to FLASH (Thanks Ronen Vainish). * Kconfig: Verify configuration settings for the LPC43xx. This includes some corrections to configuration variable names and defconfig settings. @@ -3319,13 +3319,13 @@ in all places. * drivers/enc28j60.c, include/nuttx/net/enc28j60.h, and olimex-strp711/src/up_enc28j60.c: No longer passes IRQ number - as a parameters. Instead now passes a call table to manage + as a parameter. Instead now passes a call table to manage ENC28J60 GPIO interrupts. That is because GPIO interrupts are handled in different ways by different MCUs and some do not support IRQ numbers for GPIO interrupts. * mm/mm_gran* and include/nuttx/gran.h: Add a simple granule- based allocator. The intent of this allocator is to support - simple allocation of DMA I/O buffers. The initiali check-in + simple allocation of DMA I/O buffers. The initial check-in is code complete but untested (not event built into the mm/Makefile yet. * confgs/fire-stm32v2: The board port is basically functional. @@ -3352,7 +3352,7 @@ * arch/arm/include/armv7-m/irq.h: Fix a critical bug in irqsave(). It looks like sometimes the compile will re-order some instructions inapproapriately. This end result is that interrupts will get - stuff off. + stuck off. * drivers/mtd/w25.c: Beginning of a driver for the Windbond SPI FLASH family (W25x16, W25x32, and W25x64). The initial check-in is basically just the SST25 driver with some name changes. @@ -3372,7 +3372,7 @@ I2C reset logic to recover from locked devices on the bus. * configs/*/*/Make.defs, tools/Config.mk, Makefile: Refactor all common make definitions from the various Make.defs files into - the common tools/Make.mk. Add support for a verbosity options: + the common tools/Config.mk. Add support for a verbosity options: Specify V=1 on the make command line in order to see the exact commands used in the build (Contributed by Richard Cochran). * drivers/net/enc28j60.c: The ENC28J60 Ethernet driver is @@ -3400,17 +3400,17 @@ * configs/shenzhou/src/up_lcd.c: Oops. Shenzhou LCD does not have an SSD1289 controller. Its an ILI93xx. Ported the STM3240G-EVAL ILI93xx driver to work on the Shenzhou board. - * configs/shenzhou/nxwm: Added an NxWM configuratino for the + * configs/shenzhou/nxwm: Added an NxWM configuration for the Shenzhou board. This is untested on initial check-in. It will be used to verify the Shenzhou LCD driver (and eventually the touchscreen driver). * configs/shenzhou/src/up_touchscreen.c: Add ADS7843E touchscreen support for the Shenzhou board. The initial check-in is untested - and basically a clone of the the touchscreen support fro the SAM-3U. + and basically a clone of the the touchscreen support for the SAM-3U. * tools/cfgparser.c: There are some NxWidget configuration settings that must be de-quoted. * arch/arm/src/stm32/Kconfig: There is no SPI4. Some platforms - SPI3 and some do not (still not clear). + support SPI3 and some do not (still not clear). * nuttx/configs/shenzhou: Various fixes to build new NxWM configuration. * configs/shenzhou: Oops. The Shenzhou LCD is and SSD1289, diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html index 84e0024ef..0370a708d 100644 --- a/nuttx/Documentation/NuttX.html +++ b/nuttx/Documentation/NuttX.html @@ -8,7 +8,7 @@

NuttX RTOS

-

Last Updated: August 25, 2012

+

Last Updated: September 29, 2012

@@ -480,6 +480,7 @@

  • Supports character and block drivers as well as specialized driver interfaces.
  • +
    @@ -489,6 +490,7 @@ Network, USB (host), USB (device), serial, CAN, ADC, DAC, PWM, Quadrature Encoder, and watchdog timer driver architectures.

    +
    @@ -498,6 +500,7 @@ RAMDISK, pipes, FIFO, /dev/null, /dev/zero, and loop drivers.

    +
    @@ -505,6 +508,7 @@

  • Generic driver for SPI-based or SDIO-based MMC/SD/SDH cards.
  • +
    @@ -512,6 +516,7 @@

  • Power management sub-system.
  • +
    @@ -519,6 +524,7 @@

  • ModBus support provided by built-in FreeModBus version 1.5.0.
  • + @@ -533,6 +539,7 @@

  • Fully integrated into the OS.
  • + @@ -547,6 +554,7 @@

  • TCP/IP, UDP, ICMP, IGMPv2 (client) stacks.
  • +
    @@ -554,6 +562,7 @@

  • SLIP
  • +
    @@ -561,6 +570,7 @@

  • Small footprint (based on uIP).
  • +
    @@ -568,6 +578,7 @@

  • BSD compatible socket layer.
  • +
    @@ -575,6 +586,7 @@

  • Networking utilities (DHCP server and client, SMTP client, TELNET client, FTP server and client, TFTP client, HTTP server and client). Inheritable TELNET sessions (as "controlling terminal")
  • +
    @@ -584,6 +596,7 @@ NFS Client. Client side support for a Network File System (NFS, version 3, UDP).

    +
    @@ -594,6 +607,27 @@ integrated with NXFLAT to provide true, embedded CGI.

    + + + +
    + +

    +

  • + UDP Network Discover (Contributed by Richard Cochran). +
  • +

    + + + +
    + +

    +

  • + XML RPC Server (Contributed by Richard Cochran). +
  • +

    + @@ -974,264 +1008,205 @@ -

    NuttX-6.21 Release Notes

    +

    NuttX-6.22 Release Notes

    - The 88th release of NuttX, Version 6.21, was made on August 25, 2012, and is available for download from the + The 89th release of NuttX, Version 6.22, was made on September 29, 2012, and is available for download from the SourceForge website. - Note that the release consists of two tarballs: nuttx-6.21.tar.gz and apps-6.21.tar.gz. + Note that the release consists of two tarballs: nuttx-6.22.tar.gz and apps-6.22.tar.gz. Both may be needed (see the top-level nuttx/README.txt file for build information) The change log associated with the release is available here. Unreleased changes after this release are available in SVN. These unreleased changes are also listed here.

    - This release corresponds with SVN release number: r5052 + This release corresponds with SVN release number: r5206, + Note that all SVN information has been stripped from the tarballs. + If you need the SVN configuration, you should check out directly from SVN. + Revision r5206 should equivalent to release 6.22 of NuttX 6.22:

    +
      +svn checkout -r5206 svn://svn.code.sf.net/p/nuttx/code/trunk nuttx-code
      +
    +

    Or

    +
      +svn checkout -r5206 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code
      +
    +

    Additional new features and extended functionality

      -
    • Core -
        -
      • - Add support for multiple registered atexit() functions. -
      • -
      • - Syslog extended: - Now any character driver may be used for the debug logging device. - Mountpoint traversal logic. -
      • -
      -
    • -
    • Common Drivers -
        -
      • - Added support for the TI PGA112-7 amplifier/multiplexor. -
      • -
      -
    • -
    • NXP LPC43XX -
        -
      • - Added clock ramp-up logic to run at 204 MHz. -
      • -
      -
    • -
    • NXP LPC43XX Drivers -
        -
      • - SPIFI block driver -
      • -
      • - RS-485 support -
      • -
      • - Minimal termios support -
      • -
      • - Framework for USB0 device controller driver. -
      • -
      -
    • -
    • NXP LPC17XX Drivers -
        -
      • - Minimal termios support -
      • -
      +
    • +

      + RTOS: + Application entry point is no longer user_start, but can be configured using CONFIG_USER_ENTRYPOINT. + NuttX now supports two work queues: A lower priority work queue (for extended processing) and a higher priority work queue (for quick, high priority operations). +

    • -
    • STM32 -
        -
      • - Support for STM32 F1 "Value Line" (contributed by Mike Smith). -
      • -
      • - Add support for STM32 F107 "Connectivity Line" (contributed by Max Holtzberg). -
      • -
      • - Clock restart logic needed for recovery from low power modes. -
      • -
      +
    • +

      + Memory Management: + Added a new granule-based allocated that can be used to manage, aligned and quantized DMA memory. +

    • -
    • STM32 Drivers -
        -
      • - RTC alarm support. Usable for wakeup from sleep mode. -
      • -
      • - Minimal serial termios support. -
      • -
      • - USB OTG FS host driver (alpha). -
      • -
      +
    • +

      + File System: + Add hooks to allocate I/O memory with and external allocated (need if required by DMA). +

    • -
    • STM32 Boards -
        -
      • - Add power management hooks for the STM32F4Discovery -
      • -
      • - Add support for the Olimex STM32-P107 (contributed by Max Holtzberg) -
      • -
      +
    • +

      + Networking: + ENC28J60 driver is (finally) verified. +

    • -
    • PIC32 -
        -
      • - Add support for the Pinguino MIPS toolchain -
      • -
      +
    • +

      + Drivers: + Add hooks USB device drivers to allocate I/O memory with and external allocated (need if required by DMA). + Driver for the Windbond SPI FLASH family (W25x16, W25x32, W25x64, and others). + ADS7843E driver extended for TSC2046 and XPT2046 and verified. +

    • -
    • PIC32 Drivers -
        -
      • - GPIO driver now supports F1 analog regiaters (ANSEL) -
      • -
      +
    • +

      + ARMv7-M: + Added logic to reset the MCU using the NVIC. +

    • -
    • PIC32 Boards -
        -
      • - Add support for the PGA117 on the Mirtoo module -
      • -
      +
    • +

      + STM32: + Add support for STM32F103VET6. +

    • -
    • Calypso -
        -
      • - Add support for the SSD1783 LCD on the Compal E99 -
      • -
      +
    • +

      + STM32 Drivers: + Add logic to re-initialize UARTs a second time to enable DMA (Mike Smith). + I2C driver error recovery (Mike Smith). +

    • - -
    • Library -
        -
      • - cfsetispeed(), cfsetospeed(), tcflush(), memchr(), and memccpy(). -
      • -
      +
    • +

      + STM32 boards: + Support for USB host added add to several configurations (or at least explained in README files). + Support for the Shenzhou STM32F107 board (see www.armjishu.com). + Support for M3 Wildfire STM32F103 board (v2 and v3). +

    • -
    • Applications -
        -
      • - Port of freemodbus-v1.5.0. -
      • -
      • - Add support for testing devices with multiple ADC, PWM, and QE devices. -
      • -
      • - NSH mount command (with no arguments) will now show mounted volumes. -
      • -
      • - Added new NSH df command to show file system usage. -
      • -
      • - Extended NSH 'help' support. -
      • -
      • - NSH now catches the return value from spawned applications (provided by Mike Smith). -
      • -
      +
    • +

      + Build System:: + Kconfig string de-quoting logic. + Remove comments from defconfig files (Kate). + Add tool to create NuttX-style symbol tables. + Numerous changes to configuration logic as needed for the new mconf-based configuration (much of this from Richard Cochran). + Refactor common Make.defs logic into tools/Config.mk (Richard Cochran). +

    • -
    • Build System -
        -
      • - mkconfig will not define CONFIG_DRAM_END. -
      • -
      • - A lot of progress has been made on the automated NuttX configuration logic (Thanks go to Richard Cochran). -
      • -
      +
    • +

      + Library: + Configurable terse output from strerror(). + Added perror() (Kate). + Add %n format to sscanf() (Kate). +

    • -
    • Documentation -
        -
      • - Document ways to customize the behavior of NSH -
      • -
      +
    • +

      + Applications: + Numerous changes and extensions to the old uIP web server (from Kate and Max Holtzberg, see the ChangeLog for specific extensions). + UDP network discovery utility (Max Holtzberg). + Embeddable Lightweight XML-RPC Server (http://www.drdobbs.com/web-development/an-embeddable-lightweight-xml-rpc-server/184405364, Max Holtzberg). +

    - -

    Bugfixes (see the change log for details):

    +

    + Bugfixes (see the change log for details) + Some of these are very important (marked critical): +

      -
    • Serial drivers (all) -
        -
      • - Fix ioctl() return value. -
      • -
      • - Common "upper half" serial driver will now return with EINTR if a serial wait is interrupted by a signal. -
      • -
      +
    • +

      + RTOS: + Fixes to priority inheritance logic (critical). + waitpid() critical section. + Assertion in work_cancel() (Mike Smith). + mmap() (Kate). +

    • -
    • FAT -
        -
      • - Fix statfs() file name length -
      • -
      +
    • +

      + FAT File System: + Improper Boolean expression caused un-necessary writes and performance issues (critical, Ronen Vainish). +

    • -
    • NXP LPC43xx -
        -
      • - Clock configuration -
      • -
      +
    • +

      + Networking: + Remove an un-necessary delay from recvfrom(). + This greatly improves network performance (critical, Max Holtzberg). +

    • -
    • STM32 -
        -
      • - Pinmap fixes -
      • -
      • - SPI driver re-initialization -
      • -
      +
    • +

      + Graphics: + NX parameter checking errors. +

    • -
    • STM32 Boards -
        -
      • - Correct and lower SDIO frequency for F2 and f4 boards -
      • -
      +
    • +

      + Drivers: + Fix double release of memory in SDIO-based, MMC/SD driver (Ronen Vainish). +

    • -
    • AVR -
        -
      • - C++ build issues -
      • -
      +
    • +

      + LPC17xx: + Ethernet driver fixes needed for certain PHYs (Kate). +

    • -
    • Power Management (PM) -
        -
      • - Fix a place where interrupts were not be re-enabled -
      • -
      +
    • +

      + AVR: + Fix build error (Richard Cochran). +

    • -
    • Applications -
        -
      • - Fix NSH application start-up race condition -
      • -
      +
    • +

      + STM32: + USB OTG FS host driver NAKing an retries. + Power management compilation errors (Diego Sanchez). + Missing SPI3 remap logic. +

    • -
    • Library -
        -
      • - Fieldwidth and justification for %s format. -
      • -
      • - Fixed several issues with presenting floating point numbers. -
      • -
      • - NULL definition for C++ -
      • -
      +
    • +

      + STM32 Drivers: + Fix for Ethernet errata for STM32F107 (critical). + Ethernet buffer alignment check. + Add "kludge" to Ethernet driver to handle DM9161 PHY which (at least on the Shenzhou board), sometimes does not come up correctly. +

      +
    • +
    • +

      + Applications: + THTTPD (Kate). + NSH ping when IP address is on a different network (Darcy Gong). +

      +
    • +
    • +

      + Library: + fread(), fflush(), fdopen(): Fix error handling logic (Ronen Vainish). + Fix some field-width handling issues in sscanf() +

    + As well as other, less critical bugs. See the ChangeLog for additional, detailed changes.

    @@ -1450,8 +1425,8 @@ but only partially tested. Additional features are needed: USB driver, MMC integration, to name two (the slot on the board appears to accept on MMC card dimensions; I have only SD cards). - An SPI-based ENC29J60 Ethernet driver for add-on hardware is under development and - should be available in the NuttX 5.5 release. + An SPI-based ENC28J60 Ethernet driver for add-on hardware is available and + but has not been fully verified on the Olimex board (due to issues powering the ENC28J60 add-on board).

    Development Environments: @@ -3232,284 +3207,364 @@ Other memory:

      -nuttx-6.21 2012-08-25 Gregory Nutt <gnutt@nuttx.org>
      -
      -    * configs/lpc4330-xplorer/up_nsh.c:  Add support for a basic SPIFI block
      -      driver for use by NSH.  Does not work!  Crashes on first SPIFI write.
      -    * configs/lpc4330-xplorer/*/defconfig: Calibrate delay loops (this is
      -      based on the current "slow" 72MHz M4 clock and will need to be
      -      re-calibrated when this is increased).
      -    * configs/stm3220g-eval/include/board.h and configs/stm3240g-eval/include/board.h:
      -      The SDIOCLK frequency in the F2 and F4 derives for PLL48CLK and not HCLK
      -      so that the SDIOCLK input frequency should always be 48MHz.
      -    * sched/os_internal.h, sched_setupidlefiles.c, sched_setuptaskfiles.c, and
      -      sched_setupidlefiles.c:  Detangle some conditional compilation.  Allow for
      -      a perverse configuration that has socket descriptors and streams but no file
      -      descriptors (sure, why not?).
      -    * sched/: Stylistic clean-up of all files.  Some of these files are pretty old
      -      and do not follow current NuttX coding standards in detail.
      -    * fs/: More stylistic file clean-up.
      -    * mm/: More stylistic file clean-up.
      -    * drivers/ and drivers/serial/: More stylistic file clean-up.
      -    * arch/arm/src/lpc43xx/lpc43_clockconfig.c:  Fix PLL1 bit manipulation logic.
      -      Critical bugfix! This would often cause the LPC43xx to fail to boot.
      -    * arch/arm/src/lpc43xx/lpc43_rgu.c:  The soft reset logic called from the
      -      beginning of __start seems cause problems.  A magic delay seems to improve
      -      the logic some.  But I suspect that real fix is to get rid of all of the
      -      soft reset logic.  This would also be a critical bugfix if I believed
      -      that it really fixed all of the issues.
      -    * arch/arm/src/lpc43xx/chip/lpc43_cgu.h:  Fix a bit mask in the PLL1
      -      control register.  Critical bugfix.
      -    * arch/arm/src/lpc43xx/lpc43_clockconfig.c and configs/lpc4330-xplorer/include/board.h:
      -      Implement PLL1 ramp-up logic; Now the LPC43xx is running at 204MHz.
      -    * configs/lpc4330-xplorer/*/defconfig:  Re-calibrated delay loops using
      -      the 204MHz clock.  The LPC43xx ripping rips!  This calibration was performed
      -      with symbols enabled and all optimization disabled.  It will need to be
      -      better recalibrated again down the road.
      -    * arch/arm/src/stm32/stm32_exti.c:  Renamed to rch/arm/src/stm32/stm32_exti_gpio.c
      -      to make a little room in the file name space.
      -    * arch/arm/src/stm32/stm32_exti_alarm.c:  Add initial logic to attached the
      -      RTC alarm EXTI interrupt.  This is work be performed mostly by Diego Sanchez.
      -    * include/: More stylistic file clean-up.
      -    * arch/arm/src/lpc43xx/lpc43_spifi.c, lpc43_spifi.h, and chip/lpc43_spifi.h:  Add
      -      logic to configure and initialize the SPIFI device (does not yet work).
      -    * configs/lpc4330-xplorer/include/board.h:  Reduce SPI SCLK value.
      -    * arch/arm/src/lpc43xx/lpc43_spifi.c, lpc43_spifi.h, and chip/lpc43_spifi.h:
      -      Logic completely redesigned.  It now creates an MTD driver to access SPIFI...
      -      but the driver still does not work.
      -    * arch/arm/src/stm32 and arch/arm/include/stm32: Make name of RTC ALARM interrupt
      -      common on STM32 F1,2,4
      -    * arch/arm/src/stm32 and arch/arm/include/stm32: Add support for the
      -      STM32F100x "Value Line" devices. This includes changes to stm32F10xx_rcc.c that
      -      add the ability to run the chip off the internal oscillator.  There is no open
      -      board configuration for this part yet (the STM32VLDiscovery would be a candidate).
      -      Contributed by Mike Smith.
      -    * arch/arm/src/stm32: Fixed typos in conditional compilation in the CAN and DMA
      -      and some pin configuration.  This would have caused problems for STM32 F107xx.
      -      Typos noted by Mike Smith.
      -    * arch/arm/src/lpc43xx/lpc43_serial.c:  Add support for certain RS-485 features
      -    * lib/termios/lib_cfsetispeed.c, lib_cfsetospeed.c, lib_tcflush.c:  Add
      -      simple implementations of cfsetispeed(), cfsetospeed(), and tcflush().
      -    * include/sys/str_tty.h, lib/lib_setspeed.c, lib_getspeed.c, and lib_resetspeed.c:
      -      Add APIs to support setting non-standard BAUD values not supported by POSIX
      -      termios.  These are non-standard interfaces but have a precedence:  There are
      -      similar interfaces in AIX.
      -    * include/sys/str_tty.h, lib/lib_setspeed.c, lib_getspeed.c, and lib_resetspeed.c:
      -      Sigh... removed.  We don't need any more almost standard interfaces!  (SVN
      -      revision 4968 if you want the short-lived code).
      -    * include/termios.h and lib/termios/*:  Open the existing, standard termios
      -      interfaces to permit some non-standard baud settings.  The new termios definitions
      -      still supports the POSIX standard except that it does not strictly enforce
      -      baud rate settings, permitting some non-portable, but useful baud rate settings
      -      (this is what the short-lived AIX-like interfaces would have accomplished as well).
      -    * include/termios.h and lib/termios/*:  Redesigned yet again (this is getting
      -      painful.  NuttX now supports the BOTHER baud setting just as Linux does.  termios
      -      Bxxx definitions are again encoded; cf[set|get][o|i]speed now deal with only the
      -      encoded values.  If the encoded baud is set to BOTHER, then the values in the (non-
      -      standard) c_ispeed and c_ospeed baud values may be accessed directly.
      -    * arch/arm/src/stm32/stm32_serial.c:  Add minimal termios support for the STM32
      -      (BOTHER style baud settings only).  Contributed by Mike Smith.
      -    * configs/lpc4343-xplorer/src:  Clean up SPIFI-library based build to that it
      -      actually works.
      -    * arch/arm/src/lpc43xx/lpc43_spifi.c:  Add support for verification to writes.
      -      Add debug option to dump buffers.  Several bugfixes... almost works.
      -    * include/termios.h, lib/termios/*, and arch/arm/src/stm32/stm32_serial.c: :
      -      BOTHER is gone again.
      -    * arch/arm/src/stm32/stm32_sdio.c and chip/stm32f20xx_pinmap.h:  STM32 F2 SDIO
      -      fixes from Gary Teravskis and Scott Rondestvedt.
      -    * include/termios.h and lib/termios/*:  Replace cfsetispeed and cfsetospeed with
      -      cfsetspeed (with definitions for the input/outputs in termios.h).
      -    * configs/stm32f4discovery/src and configs/stm32f4discovery/pm:  Add a power
      -      management configuration for the STM32F4Discovery and supporting logic.  This
      -      check-in also includes some fixes for the F4 RTC alarm logic.
      -    * drivers/input/pga11x.c and include/nuttx/input/pga11x.h:  Add support for the
      -      TI PGA112/3/6/7 amplifier/multiplexer parts.
      -    * configs/mirtoo/README.txt, nsh/defconfig, and nxffs/defconfig:  Add support
      -      for the PGA117 on the Mirtoo module.
      -    * drivers/analog/pga11x.c and include/nuttx/analog/pga11x.h:  These belong in
      -      the analog subdirectories, not input.
      -    * configs/compal_e99/src/ssd1783.c and /ssd1783.h:  Drivers for the SSD1783
      -      LCD found in the Motorola C155 telephone.  The driver is specific to the C155
      -      because it uses the uwire transport.  Contributed by Denis Carilki and
      -      Alan Carvalho de Assis.
      -    * drivers/power/pm_changestate.c.  Correct a case where interrupts were not
      -      being re-enabled.  Found by Diego Sanchez.
      -    * configs/mirtoo/nxffs/defconfig:  This Mirtoo NXFFS configuration now uses the
      -      open Pinguino toolchain by default.  This is necessary because the free C32
      -      toolchain does not support any optimization and the unoptimized NXFFS image
      -      hits the PIC32MX2 FLASH size (128K).  There is plenty of room to grow using
      -      the Pinguino toolchain with -O2 optimization.
      -    * configs/mirtoo/src/up_adc.c.  This is just a stub for now, but this is
      -      where Mirtoo ADC logic will eventually need to go.
      -    * arch/mips/src/pic32mx/pic32mx-gpio.c:  Now supports the PIC32MX1/2 ANSEL
      -      IOPORT register.
      -    * lib/string/lib_memchr.c:  Add support for memchr() (contributed by Mike Smith)
      -    * lib/string/lib_memccpy.c:  Add support for memccpy()
      -    * arch/arm/src/lpc17xx/lpc17_serial.c:  Now supports ioctl commands to change
      -      the baud using tcsetattr() (contributed by Chris Taglia).
      -    * arch/*/src/*_serial.c: Fix ioctl method return values.  These methods
      -      should return a negated errno value; they should not set the errno
      -      variable.
      -    * sched/on_exit.c, sched/task_exithook.c, and include/nuttx/sched.c:  Add
      -      support for multiple registered on_exit() functions if CONFIG_SCHED_ONEXIT_MAX
      -      is defined.
      -    * drivers/syslog/ramlog.c: Move the RAM SYSLOG device into drivers/syslog
      -      so that it will be in the same directory as some new SYSLOGing devices
      -      in the works.
      -    * include/nuttx/syslog.h and drivers/syslog/ramlog.c:  The SYSLOG putc function
      -      now has a common name that is independent of the device that provides the
      -      SYSLOG.
      -    * include/nuttx/syslog.h and drivers/syslog/syslog.c:  This is a new, generic
      -      SYSLOG device that can redirect debug output to any character device or file.
      -      So you can log debug output to a file or you can put the console on /dev/ttyS0
      -      and the debug output on /dev/ttyS1.
      -    * arch/arm/src/lpc43xxl/lpc43_spifi.c: Correct an addressing error in the LPC43
      -      SPIFI MTD driver
      -    * drivers/syslog/syslog.c and fs/fs_syslog.c:  Moved the generic syslog logic
      -      from drivers/syslog to fs/ where is belongs.  Especially after realizing that
      -      the syslog logic is going to have to some internal FS operations in order
      -      to realize a totally thread-independent SYSLOG interface.
      -    * arch/arm/src/stm32/stm32*_rcc.c and .h:  If CONFIG_PM is defined, add a
      -      function called stm32_clockenable() that can be used by PM logic to re-start
      -      the PLL after re-awakening from deep sleep modes.
      -    * fs/fs_foreachinode.c and fs/fs_foreachmountpoint.c:  Add logic to traverse
      -      inodes and mountpoints in the NuttX pseudo-file system.
      -    * fs/fat/fs_fat32.c: Max. filename length reported by statfs() was wrong
      -      if FAT long file names were enabled.
      -    * lib/stdio/lib_libvsprintf.c:  Fieldwidth and justification were not
      -      supported for the %s format.  As a result, %s, %12s, and %-12s all
      -      produced the same output.
      -    * lib/stdio/lib_libdtoa.c:  Fix several issues with presenting floating
      -      point numbers (conversions are fine, but presentation was bad).  This
      -      is a critical bug fix if you use printf or sprintf to deal with floating
      -      point numbers.
      -    * lib/stdio/lib_libdtoa.c and lib_libvsprintf.c:  Correct some floating
      -      point options.
      -    * arch/arm/lpc43xx/lpc32_usb0dev.c:  Add framework for development of
      -      an USB0, device-side driver for the LPC43XX.  The initial check-in,
      -      however, is simply for the LPC31xx driver with name changes.  The
      -      LPC31xx has the same USB IP, but will require some additional initialization
      -      (and lots of testing) before it can be used with the LPC43xx.
      -    * nuttx/Documentation/NuttShell.html:  Added a section covering ways to
      -      customize the behavior of NSH.
      -    * arch/arm/src/stm32/chip/stm32f1*_pinmap.h: STM32 CAN TX/RX pins reversed;
      -      inconsistent conditional compilation.  Reported by Max Holtzberg.
      -    * arch/arm/*/stm32:  Add support for STM32 F107 "Connectivity Line" 
      -      Ethernet (contributed by Max Holtzberg).
      -    * configs/olimex-stm32-p107:  Add board support for the Olimiex STM32-P107
      -       board (contributed by Max Holtzberg).
      -    * arch/arm/src/stm32/stm32f2xx_dma.c, stm32f4xx_dma.c, stm32_serial.c, and
      -      stm32_spic.c:  DMA priority was getting zeroed by STM32 F2/F4 DMA drivers
      -      so that all DMAs ran at the lowest priority.
      -    * configs/stm3240g-eval/include/board.h and configs/stm3220:  Drop SD card
      -      frequency from 24 to 16 MHz.  Apparently 24 MHz is too fast for the board.
      -      This (plus the change to the STM32 DMA (above) fixes SDIO DMA on the
      -      STM3240G-EVAL (and probably STM3220G-EVAL -- untested).
      -    * arch/arm/src/stm32/stm32f2xx_dma.c and stm32f4xx_dma.c: Backed out the
      -      DMA priority change just above.  The reduced SD card frequency was
      -      necessary and sufficient to resolve the problem.
      -    * drivers/serial/serial.c:  open, read, write, and poll methods may now
      -      abort return EINTR (or a short transfer size) if a signal is received
      -      while waiting to receive or send serial data.  This behavior is required
      -      by POSIX.
      -    * include/sys/types.h:  Define NULL to be (0) if __cplusplus is defined.
      -      (contributed by Mike Smith)
      -    * include/ctype.h: Remove a stray semi-colon in a definitions (Thanks
      -      Mike Smith).
      -    * configs/.../Make.defs.  Fix C++ include path set-up in Make.defs file
      -      for all 8-bit AVR platforms (Thanks Richard Cochran).
      -    * lib/stdio/lib_*stream.c:  Revised to handle new error return values from
      -      serial.c.
      -    * arch/arm/src/stm32/stm32_spi.c:  SPI driver can now service re-
      -      initialization (Mike Smith).
      -    * tools/mkconfig.c:  If CONFIG_DRAM_END is not specified, this tool
      -      will provide default definition of (CONFIG_DRAM_START + CONFIG_DRAM_SIZE)
      -    * arch/arm/src/stm32/stm32_otgfshost.c:  Renamed from stm32_usbhost.c.
      -      This is nearly code complete and, with any luck, will be available
      -      in NuttX-6.21.
      -    * configs/*/defconfig:  Update all defconfig files to remove syntax
      -      that is incompatible with the mconf configuration tool.
      -    * arch/arm/src/stm32/stm32_otgfshost.c:  This driver now appears to be
      -      functional (although more testing is necesary).
      -
      -apps-6.21 2012-08-25 Gregory Nutt <gnutt@nuttx.org>
      -
      -    * apps/include/: Stylistic clean-up of all header files.
      -    * apps/modbus and apps/include/modbus:  A port of freemodbus-v1.5.0
      -      has been added to the NuttX apps/ source tree.
      -    * apps/examples/modbus:  A port of the freemodbus-v1.5.0 "demo"
      -      program that will be used to verify the FreeModBus port
      -    * apps/modbus:  Don't use strerror().  It is just too big.
      -    * apps/modbus:  Add CONFIG_MB_TERMIOS.  If the driver doesn't support
      -      termios ioctls, then don't bother trying to configure the baud, parity
      -      etc.
      -    * apps/nshlib:  If waitpid() is supported, then NSH now catches the
      -      return value from spawned applications (provided by Mike Smith)
      -    * apps/nshlib:  Lock the scheduler while starting built-in applications
      -      in order to eliminate race conditions (also from Mike Smith).
      -    * apps/examples/adc, pwm, and qencoder:  Add support for testing
      -      devices with multiple ADC, PWM, and QE devices.
      -    * apps/nshlib/nsh_mntcmds.c:  Separated mount-related commands out of
      -      nsh_fscmds.c.  Extended to the mount command so that if no arguments
      -      are provided, then the current mountpoints are enumerated.
      -    * apps/nshlib/nsh_mntcmds.c:  Add an NSH df command to list the
      -      properties of mounted file systems.
      -    * apps/nshlib/nsh_parse.c:  Extend help command options.  'help' with
      -      no arguments outputs a short list of commands.  With -v lists all
      -      command line details.  A command name can be added to just get
      -      help on one command.
      -    * system/readline.c:  If character input/output is interrupted by a
      -      signal, then readline() will try the read/write again.
      -    * apps/*/Make.defs:  Numerous fixes needed to use the automated
      -      configuration (from Richard Cochran).
      -
      -NxWidgets-1.2 2012-06-15 Gregory Nutt <gnutt@nuttx.org>
      -
      -    * NXWidgets::CCallback: callback arguement is now type CCallback and not
      -      CWidgetControl;  Added a method to redirect keyboard contacts to either
      -      the widgets in the window (via CWidgetControl) or to an NxConsole (via
      -      nxcon_kbdin()).
      -    * NXWidgets::INxWindow, CBgWindow, CNxTkWindow, CNxToolbar, CNxWindow:
      -      Now pass the CCallback intances as the callback argument instead of
      -      the CWidgetControl instance.  New method redirectNxConsole() will
      -      support redirection of any window keyboard input to the NxConsole
      -      (via CCallback).
      -    * NxWM:CNxConsole:  Configures the NxConsole window to redirection keyboard
      -      input to the NxConsole; redirects standard input to the NxConsole
      -      device driver.
      -    * NxWM:CKeyboard:  Add a new class that implements a keyboard listener
      -      thread.  This thread reads from /dev/console and injects the keyboard
      -      input into NX.  NX will determine which window is at the top of the
      -      heirarchy and re-direct the keyboard input to only that top window.
      -      This solves an important problem with, for example, running multiple
      -      copies of the NxConsole:  On the copy of the NxConsole at the top of
      -      the heirarchy should get the keyboard input.
      -    * UnitTests/nxwm/main.cxx: Now starts the keyboard thread if
      -      CONFIG_NXWM_KEYBOARD is defined.
      -    * NxWM::CTaskbar:  After drawing the task bar, need to raise the
      -      application window otherwise the taskbar will be on the top and
      -      keyboard input will not be received by the top application.
      -    * NxWM::CTaskbar:  Bugfix... previous window should not be minimized
      -      when a new window is started.  It should stay in a maximized state
      -      so that it will re-appear with the window above it is closed or
      -      minimized.
      -    * NxWM::CHexCalculator:  Add a hexadecimal/decimal calculator
      -      example.
      -    * NXWidgets::CNxTkWindow:  Back out height adjustment in the getSize()
      -      method.  The code was correct as it was before.
      -    * NXWidgets::CButtonArray and NXWidgets::CGraphicsPort:  There is
      -      a kludge in there to handle the case where we cannot read the
      -      background data because the LCD does not support read operations.
      -      In that case, we just use the default background color.  However,
      -      that doesn't work either for the case where the background color
      -      changes when the widget is selected.  Then the background color
      -      in the font is wrong.  Fixed in CButtonArrary, but the problem
      -      probably exists in other places as well.
      -    * NxWM:  Increase default spacing of icons on the Start Window.
      -    * NxWM::CHexCalculator:  Fix some non-standard calculator behavior
      -      after = is pressed.  Use upper case hex.  Increase font size.
      -    * nxwm/Makefile:  Fix error that creapt in during some other
      -      recent check-ins.
      +nuttx-6.22 2012-09-29 Gregory Nutt <gnutt@nuttx.org>
      +
      +    * include/semaphore.h, sched/sem_holders.c, and lib/semaphore/sem_init.c:
      +      Fix some strange (and probably wrong) list handling when
      +      CONFIG_PRIORITY_INHERITANCE and CONFIG_SEM_PREALLOCHOLDERS are defined.
      +      This list handling was probably causing errors reported by Mike Smith
      +    * sched/sched_waitpid.c: Fix a possible issue with logic logic that
      +      should be brought into a critical section (suggested by Mike Smith)
      +    * sched/sched_setuptaskfiles.c: Should be 'struct socket' not
      +      'struct sockets'.  How did this compile before? (found by Kate)
      +    * syscall/syscall.csv:  Fix prototype for usleep() and prctl() (also
      +      from Kate).
      +    * arch/arm/src/lpc17xx/lpc17_ethernet.c:  Conditionally elide setting PHY
      +      speed/duplex.  This does not work for certain PHYs.  Still some unresolved
      +      issues (also from Kate).
      +    * tools/Config.mk, Makefile, configs/*/Make.defs:  Add a new Makefile
      +      fragment to de-quote certain strings from the Kconfig logic that
      +      need to be used at path segments (Richard Cochran).
      +    * arch/arm/src/stm32/stm32_usbotghost.c:  The STM32 USB host driver only
      +      works with debug turned on.  The problem appears to be that with debug
      +      OFF, there are more NAKs occuring in more places than before and this
      +      reveals a variety of errors.  This check in improves NAK robustness
      +      for control transfers but does not resolve all of the issues.
      +    * configs/stm3220g-eval/*/defconfig:  Calibrated delay loop.  It had
      +      never been calibrated was way off.
      +    * sched/sem_holder.c: Add logic to handler some priority inheritance
      +      cases when sem_post() is called from an interrupt handler.  The
      +      logic is clearly wrong, but it is not known if this is the
      +      cause of any known bugs.
      +    * lib/stdio/lib_perror():  Add perror().  Contributed by Kate.
      +    * lib/string/lib_strerror():  Add option CONFIG_LIBC_STRERROR that
      +      is now required to enabled strerror().  Add an option
      +      CONFIG_LIBC_STRERROR_SHORT that can be used to output shortened
      +      strings by strerror().
      +    * arch/arm/src/stm32/stm32_usbotghost.c:  Finally... the USB OTG FS
      +      appears to handle NAKing correctly.
      +    * configs/stm32f4discovery/*:  Added and verifed support for USB OTG FS
      +      host on the STM32F4Discovery board.
      +    * configs/*/defconfig: Remove configuration documentation from config
      +      files.  It is redundant, error-prone, and difficult to maintain.
      +      Configuration documentation is available in configs/README.txt for
      +      common configurations and in configs/*/README.txt for board and MCU-
      +      specific configurations.
      +    * configs/stm3240g-eval: Add USB host support.
      +    * sched/os_bring.c, configs/*/defconfig, tools/mkconfig.c, and others:  Added
      +      configuration variable CONFIG_USER_ENTRYPOINT that may be used to change
      +      the default entry from user_start to some other symbol.  Contributed by
      +      Kate. NOTE: This change does introduce a minor backward incompatibility.
      +      For example, if your application uses NSH as its start-up program, then your
      +      build will now fail because it will be unable to find "user_start".  The fix
      +      for this link failure is to add the following to your configuration file:
      +      CONFIG_USER_ENTRYPOINT="nsh_main".
      +    * libs/stdio/lib_libfread.c and lib_*flush*.c:  Correct a couple of
      +      error cases where the lib semaphore was not be released on error
      +      exits (thanks Ronen Vainish).  Also, improved some error reporting:
      +      the generic ERROR was being used instead of the specific errno
      +      value; the errno variable was not always set correctly.
      +    * tools/mkfsdata.pl: The uIP web server CGI image making perl script was
      +      moved from apps/netutils/webserver/makefsdata to nuttx/tools/mkfsdata.pl
      +      (Part of a larger change submitted by Max Holtzberg).
      +    * configs/stm3240g-eval/script/ld.script:  All of the identical ld.script
      +      files for the STM3240G-EVAL were replaced by one version in this directory.
      +    * configs/stm3240g-eval/webserver:  Configuration submitted by Max Holtzberg
      +      for testing the changes to the uIP web server (see apps/ChangeLog.txt).
      +    * lib/stdio/lib_perror.c:  Remove CONFIG_LIBC_PERROR_DEVNAME.  What was I
      +      thinking?  Arbitrary streams cannot be shared by different tasks.
      +    * tools/mksyscall.c, csvparser.c, and csvparser.h: Separate CSV parsing
      +      logic from mksyscall.c into files where it can be shared.
      +    * tools/mksymtab.c:  Add a tool that can be used to convert a CSV file
      +      into a NuttX-style symbol table.
      +    * sched/work_cancel.c:  Fix a bad assertion (reported by Mike Smith)
      +    * configs/stm3210e-eval/src/up_idle.c:  Correct some power management
      +      compilation errors (reported by Diego Sanchez).
      +    * include/nuttx/wqueue.h, sched/work*, and others:  Added logic to support
      +      a second, lower priority work queue (CONFIG_SCHED_LPWORK).
      +    * arch/arm/src/stm32/stm32_dma.c, chip/stm32*_memorymap.h:  FSMC SRAM is
      +      only 16-bits wide and the SDIO DMA must be set up differently.
      +    * arch/arm/src/stm32/stm32_dma.c:  Back out the 16-bit DMA change. It
      +      is incorrect.
      +    * configs/:  Make use of UART4/5 vs USART4/5 consistent in all places.
      +    * Kconfig: Serial 2STOP setting must be integer 0/1, not a boolean.
      +    * lib/misc/sendfile.c and include/sys/sendfile.h:  Add a Linux style
      +      sendfile() (non-standard!)
      +    * Kconfig: Refactor serial settings (moved from chip to drivers/serial).
      +      AVR "teensy" now builds with Kconfig (contributed by Richard Cochran).
      +    * Kconfig: Add configuration settings for the LPC17xx
      +    * Kconfig: Add configuration settings for the LM3S (from Richard Cochran).
      +    * Kconfig: Verify configuration settings for the STM32.  This includes
      +      changes in the way that the external SRAM is configured:  Define
      +      CONFIG_HEAP2_SIZE (decimal) instead of CONFIG_HEAP2_END (hex).
      +    * tools/configure.sh:  Don't append the apps directory path setting
      +      if the correct setting is already in defined in the defconfig file.
      +    * fs/fat/fs_utils.c:  Improperly constructed bool expression.  This
      +      would cause many unnecessary writes to FLASH (Thanks Ronen Vainish).
      +    * Kconfig: Verify configuration settings for the LPC43xx.  This includes
      +      some corrections to configuration variable names and defconfig settings.
      +    * Kconfig: Add and verify configuration settings for the LPC31xx.
      +    * arch/arm/src/stm32/stm32_uart.h and stm32_serial.c:  Add logic to
      +      re-initialize the console UART as needed to enable DMA on the
      +      console UART (contributed by Mike Smith).
      +    * net/recvfrom.c, net/Kconfig, include/nuttx/net/uipopt.h: Remove delay
      +      after receiving data.  That has historical reasons to be there (it
      +      was needed before read-ahead buffering was added), but kills performance.
      +      (Noted by Max Holtzberg).
      +    * configs/shenzhou:  Add beginnings of a board configuration for the
      +      Shenzhou STM32107 board (see www.armjishu.com).  Very little is in
      +      place as of this initial check-in.
      +    * QEMU: Fixes from Richard Cochran to build QEMU with Kconfig files.
      +    * arch/*/src/Makefile:  Remove some old logic that was kicked off
      +      when CONFIG_BOOT_RUNFROMFLASH=y.  The old logic used to use
      +      objcopy to move sections.  Newer logic changes the load position
      +      of sections in the the linker script.  As far as I can tell, there
      +      is nothing in the source tree now that depends on the old way of
      +      doing things (if I am wrong, they will need a change to the linker
      +      script).
      +    * configs/fire-stm32v2:  Configuration for the M3 Wildfire board.  I
      +      don't know very much about this board other than is has an
      +      STM32F103VET6 chip, LCD, touchscreen, and ENC28J60 network.  Very
      +      little is in place on the initial check-in.
      +    * configs/shenzhou: Coding for the Shenzhou board port is complete,
      +      but tested has been deferred until I get the right tools.
      +    * arch/arc/include/stm32/chip.h and arch/arm/src/stm32/chip.h:
      +      Add support for the STM32F103VET6.
      +    * fs/fs_fdopen.c: Bad check for failure to allocate memory.  (Noted
      +      by Ronen Vainish).
      +    * drivers/mmcsd/mmcsd_sdio.c: If the MMC/SD driver were ever
      +      uninitialized then there would be a double release of memory
      +      (Noted by Ronen Vainish).
      +    * fs/mmap/fs_rammap.c:  Fix logic error and errno check (contributed
      +      by Kate).
      +    * arch/avr/src: Fixes from AVR32 build errors that have crept in
      +      over the time; incorporated Kconfig for AVR3 (Richard Cochran).
      +    * fs/fat and include/nuttx/fs/fat.h: The FAT file system allocates
      +      memory for sector I/O buffers used to exchange data with the
      +      configured block driver.  In some contexts, the block driver may
      +      require DMA-capable memory.  If CONFIG_FAT_DMAMEMORY is defined,
      +      then the FAT FS will use platform-provided DMA memory allocators
      +      to allocate the block driver I/O buffers.
      +    * CONFIG_NET_ENC28J60 renamed CONFIG_ENC28J60 to be consistent
      +      in all places.
      +    * drivers/enc28j60.c, include/nuttx/net/enc28j60.h, and 
      +      olimex-strp711/src/up_enc28j60.c:  No longer passes IRQ number
      +      as a parameter.  Instead now passes a call table to manage
      +      ENC28J60 GPIO interrupts.  That is because GPIO interrupts are
      +      handled in different ways by different MCUs and some do not
      +      support IRQ numbers for GPIO interrupts.
      +    * mm/mm_gran* and include/nuttx/gran.h:  Add a simple granule-
      +      based allocator.  The intent of this allocator is to support
      +      simple allocation of DMA I/O buffers.  The initial check-in
      +      is code complete but untested (not event built into the
      +      mm/Makefile yet.
      +    * confgs/fire-stm32v2: The board port is basically functional.
      +      Not all features have been verified.  The ENC28J60 network
      +      is not yet functional.
      +    * configs/stm3240g-eval/discover:  A configuration for testing
      +      the UDP discovery utility.  Contributed by Max Holtzberg.
      +    * mm/README.txt:  Add a new README file.
      +    * include/nuttx/usb/usb.h, arch/*/src/*usb.c, and arch/*/src/*otg*.c:
      +      Add hooks to to use common, external DMA buffer allocation
      +      implementation.
      +    * net/recvfrom.c: Don't block in recvfrom if (1) read-ahead buffering
      +      is enabled and (2) some data was obtained from read-ahead buffers.
      +      Blocking is a bad idea in that case because there is no timeout!
      +      (submitted by Max Holtzberg).
      +    * configs/stm3240g-eval/xmlrpc: An example configuration for the
      +      Embeddable Lightweight XML-RPC Server at apps/examples/xmlrpc.
      +      See http://www.drdobbs.com/web-development/\
      +      an-embeddable-lightweight-xml-rpc-server/184405364 for more info.
      +      Contributed by Max Holtzberg.
      +    * configs/*/nxwm/defconfig and sched/task_exithook.c: Fixes for
      +      bugs that crept in during recent changes.  (Submitted by Max
      +      Holtzberg).
      +    * arch/arm/include/armv7-m/irq.h:  Fix a critical bug in irqsave().
      +      It looks like sometimes the compile will re-order some instructions
      +      inapproapriately.  This end result is that interrupts will get
      +      stuck off.
      +    * drivers/mtd/w25.c:  Beginning of a driver for the Windbond SPI
      +      FLASH family (W25x16, W25x32, and W25x64).  The initial check-in
      +      is basically just the SST25 driver with some name changes.
      +    * arch/arm/include/armv7-m/irq.h and arch/arm/src/stm32/stm32_spi.c:
      +      Back out the last change in irq.h.  It is (most likely) fine the
      +      way it was.  The really interrupt related problem was in stm32_spi.c:
      +      When SPI3 is not enabled, then the irqrestore() falls in the
      +      else clause.
      +    * include/nuttx/compiler.h and other files:  Moved always_inline
      +      and noinline __attributes__ here.  Also replaced all occurrences
      +      of explicit __atributes__ in other files with definitions from
      +      this header file.
      +    * drivers/mtd/w25.c:  The Windbond SPI FLASH W25 FLASH driver is
      +      code complete (but still untested).
      +    * arch/arm/src/stm32/stm32_i2c.c:  I2C improvements from Mike Smith.
      +      Unified configuration logic; dynamic timeout calculations;
      +      I2C reset logic to recover from locked devices on the bus.
      +    * configs/*/*/Make.defs, tools/Config.mk, Makefile:  Refactor all
      +      common make definitions from the various Make.defs files into
      +      the common tools/Config.mk.  Add support for a verbosity options:
      +      Specify V=1 on the make command line in order to see the exact
      +      commands used in the build (Contributed by Richard Cochran).
      +    * drivers/net/enc28j60.c:  The ENC28J60 Ethernet driver is
      +      now functional.
      +    * configs/fire-stm32v2:  Add support or the fire-stm32v3 board as
      +      well (untested because I do not have a v3 board).
      +    * lib/stdio/lib_sscanf.c:  Add %n psuedo-format (from Kate).
      +    * lib/stdio/lib_sscanf.c:  There is an issue of handling input
      +      when (1) no fieldwidth is provided and (2) there is no space
      +      seperating the input values.  No solutions is in place for this
      +      case now (either space or a fieldwidth must be provided).  But
      +      at least some of the bad logic that attempted to handle this
      +      case has been removed (noted by Kate).
      +    * arch/arm/src/stm32/stm32_eth.c:  DMA buffer sizes must be an
      +      even multiple of 4, 8, or 16 bytes.
      +    * arch/arm/src/stm32/stm32_idle.c:  Fixes STM32F107 DMA issues:
      +      We cannot go into sleep mode while Ethernet is actively DMAing.
      +    * configs/shenzhou/src/up_ssd1289.c:  Add infrastructure to support
      +      SSD1289 LCD.  Initial checkin is just a clone of the
      +      STM32F4Discovery's FSMC-based LCD interface.  The Shenzhou
      +      will need a completely need bit-banging interface; this
      +      initial check-in is only for the framework.
      +    * configs/shenzhou/src/up_ssd1289.c:  Bit-banging driver is
      +      code complete.
      +    * configs/shenzhou/src/up_lcd.c:  Oops. Shenzhou LCD does not
      +      have an SSD1289 controller.  Its an ILI93xx.  Ported the
      +      STM3240G-EVAL ILI93xx driver to work on the Shenzhou board.
      +    * configs/shenzhou/nxwm:  Added an NxWM configuration for the
      +      Shenzhou board.  This is untested on initial check-in.  It will
      +      be used to verify the Shenzhou LCD driver (and eventually the
      +      touchscreen driver).
      +    * configs/shenzhou/src/up_touchscreen.c:  Add ADS7843E touchscreen
      +      support for the Shenzhou board.  The initial check-in is untested
      +      and basically a clone of the the touchscreen support for the SAM-3U.
      +    * tools/cfgparser.c: There are some NxWidget configuration
      +      settings that must be de-quoted.
      +    * arch/arm/src/stm32/Kconfig: There is no SPI4.  Some platforms
      +      support SPI3 and some do not (still not clear).
      +    * nuttx/configs/shenzhou: Various fixes to build new NxWM
      +      configuration.
      +    * configs/shenzhou:  Oops.  The Shenzhou LCD is and SSD1289,
      +      not an ILI93xx.
      +    * configs/shenzhou/src/up_ssd1289.c: The LCD is basically functional
      +      on the Shenzhou board.
      +    * graphics/nxmu:  Correct some bad parameter checking that caused
      +      failures when DEBUG was enabled.
      +    * arch/arm/src/armv7-m/nvic.h:  Add bit definitions for the AIRCR
      +      register.
      +    * drivers/input/ads7843.c:  Need semaphore protection in logic
      +      that samples the position.
      +    * drivers/lcd/ssd1289.c:  On some platforms we are unable to
      +      read the device ID -- reason unknown; workaround in place.
      +    * drivers/input/ads7843.c:  Add thresholding options and an
      +      option to swap X and Y positions.  Fix some logic errors in
      +      the SPI locking/selecting logic.
      +    * arch/arm/src/armv7-m/up_systemreset.c:  Add logic to reset
      +      the Cortex-Mx using the AIRCR register.  Contributed by Darcy
      +      Gong.
      +    * arch/arm/src/stm32/up_eth.c:  Add logic specifically for the
      +      DM9161 PHY.  If the DM9161 failed to initialize, then use the
      +      up_sysemreset() logic to reset the MCU.  Contributed by Darcy
      +      Gong.
      +    * arch/arm/src/stm32/stm32_gpio.c:  Add missing logic to set bit
      +      for SPI3 remap.  This fixes the XPT2046 touchscreen driver using
      +      drivers/input/ads7843.c
      +    * configs/shenzhou/src/up_ssd1289.c:  Fix naming error in
      +      conditional compilation.
      +    * configs/shenzhou/nxwm/defconfig:  Disable reading from the LCD.
      +      This does not work.  The hardware and the driver support the
      +      capability, but there is some bug that causes memory corruption.
      +      The work around for now:  Just disable reading from the LCD.
      +    * drivers/lcd/ssd1289.c:  Add some logic to reduce the amount of
      +      output when CONFIG_DEBUG_LCD is enabled.
      +    * configs/shenzhou/nxwm/defconfig:  Bug found and fixed... The
      +      original configuration had too much stuff turned on.  Reducing
      +      stack sizes, some features, and buffer sizes made the
      +      configuration reliable (Reading from the LCD is still disabled).
      +    * net/uip/uip_icmpping.c:  Fix problem that prevented ping from
      +      going outside of local network.  Submitted by Darcy Gong
      +
      +apps-6.22 2012-09-29 Gregory Nutt <gnutt@nuttx.org>
      +
      +    * apps/netutils/thttpd/thttpd_cgi.c:  Missing NULL in argv[]
      +      list (contributed by Kate).
      +    * apps/nshlib/nsh_parse.c: CONFIG_NSH_DISABLE_WGET not CONFIG_NSH_DISABLE_GET
      +      in one location (found by Kate).
      +    * apps/examples/ostest/prioinherit.c:  Limit the number of test
      +      threads to no more than 3 of each priority.  Bad things happen
      +      when the existing logic tried to created several hundred test
      +      treads!
      +    * apps/nshlib/nsh.h:  Both CONFIG_LIBC_STRERROR and CONFIG_NSH_STRERROR
      +      must be defined to use strerror() with NSH.
      +    * apps/examples/*/*_main.c, system/i2c/i2c_main.c, and others:  Added
      +      configuration variable CONFIG_USER_ENTRYPOINT that may be used to change
      +      the default entry from user_start to some other symbol.  Contributed by
      +      Kate.
      +    * apps/netutils/webserver/httpd/c:  Fix a typo that as introduced in
      +      version r4402:  'lese' instead of 'else' (Noted by Max Holtzberg).
      +    * tools/mkfsdata.pl: The uIP web server CGI image making perl script was
      +      moved from apps/netutils/webserver/makefsdata to nuttx/tools/mkfsdata.pl
      +      (Part of a larger change submitted by Max Holtzberg).
      +    * apps/netutils/webserver, apps/examples/uip, and apps/include/netutils/httpd.h:
      +      The "canned" version of the uIP web servers content that was at 
      +      netutils/webserver/httpd_fsdata.c has been replaced with a dynamically
      +      built configuration located at apps/examples/uip (Contributed by
      +      Max Holtzberg).
      +    * apps/netutils/webserver:  Several inenhancements from Kate including the
      +      ability to elide scripting and SERVER headers and the ability to map
      +      files into memory before transferring them.
      +    * apps/netutils/webserver:  Add ability to map a URL to CGI function.
      +      Contributed by Kate.
      +    * apps/nshlib/nsh_mntcmds.c: The changes of 6.21 introduced holes in the
      +      error handling:  Now the number of arguments to mount can be 0 or 4.
      +      Additional parameter checking is required to prevent mysterious errors
      +      (submiteed by Kate).
      +    * apps/netutils/webserver/httpd_mmap.c:  Fix errors when the mmap()
      +      length is zero (submitted by Kate).
      +    * apps/netutils/webserver/httpd_sendfile.c:  Add and option,
      +      CONFIG_NETUTILS_HTTPD_SENDFILE to transfer files using the NuttX
      +      sendfile() interface.
      +    * apps/netutils/discover:  A UDP network discovery utility contributed
      +      by Max Holtzberg.
      +    * apps/examples/discover:  A test example for the UDP network discovery
      +      utility (also contribed by Max Holtzberg).
      +    * apps/examples/*/main.c:  Too many files called main.c.  Each renamed
      +      to something unique so that they will not collide in the archive.
      +    * apps/netutils/xmlrpc: The Embeddable Lightweight XML-RPC Server
      +      discussed at http://www.drdobbs.com/web-development/\
      +      an-embeddable-lightweight-xml-rpc-server/184405364.  Contributed by
      +      Max Holtzberg.
      +    * apps/netutils/uip_listenon.c:  Logic in uip_server.c that creates
      +      the listening socket was moved to this new file to support re-use.
      +      Contributed by Kate.
      +    * apps/netutils/webserver/httpd.c:  The option CONFIG_NETUTILS_HTTPD_SINGLECONNECT
      +      can now be used to limit the server to a single thread.  Option
      +      CONFIG_NETUTILS_HTTPD_TIMEOUT can be used to generate HTTP 408 errors.
      +      Both from Kate.
      +    * apps/netutils/webserver/httpd.c:  Improvements to HTTP parser from
      +      Kate.
      +    * apps/netutils/webserver/httpd.c:  Add support for Keep-alive connections
      +      (from Kate).
      +    * apps/NxWidget/Kconfig:  This is a kludge.  I created this NxWidgets
      +      directory that ONLY contains Kconfig.  NxWidgets does not live in
      +      either the nuttx/ or the apps/ source trees.  This kludge makes it
      +      possible to configure NxWidgets/NxWM without too much trouble (with
      +      the tradeoff being a kind ugly structure and some maintenance issues).
      +    * apps/examples/Make.defs: Missing support for apps/examples/watchdog.
      +    * apps/NxWidgets/Kconfig:  Add option to turn on the memory monitor
      +      feature of the NxWidgets/NxWM unit tests.
      +
      +NxWidgets-1.3 2012-09-29 Gregory Nutt <gnutt@nuttx.org>
      +
      +    * UnitTests/*/main.cxx:  Change entry point name to be consistent
      +      with with entry point naming conventions introduced in NuttX
      +      6.22.
      +    * Kconfig:  Added a mconfig configuration file.  Eventually, NxWidgets
      +      needs to get hooked into the NuttX mconf configuration.  Still not
      +      exactly sure how to do that.
      +    * libnxwidgets/Makefile and NxWidgets/nxwm/Makefile:  Need updates
      +      for consistency with recent changes to NuttX build system (>= 6.22)
      +    * Kconfig:  Add option to turn on the memory monitor feature of the
      +      NxWidgets/NxWM unit tests.
       
       pascal-3.0 2011-05-15 Gregory Nutt <gnutt@nuttx.org>
       
      diff --git a/nuttx/ReleaseNotes b/nuttx/ReleaseNotes
      index 4d7211669..80362f5dd 100644
      --- a/nuttx/ReleaseNotes
      +++ b/nuttx/ReleaseNotes
      @@ -3063,3 +3063,107 @@ Bugfixes (see the change log for details) :
             for C++
       
       As well as other, less critical bugs (see the ChangeLog for details)
      +
      +NuttX-6.22
      +^^^^^^^^^^
      +
      +The 89th release of NuttX, Version 6.22, was made on September 29, 2012,
      +and is available for download from the SourceForge website.  Note
      +that release consists of two tarballs:  nuttx-6.22.tar.gz and
      +apps-6.22.tar.gz.  Both may be needed (see the top-level nuttx/README.txt
      +file for build information).
      +
      +This release corresponds with SVN release number: r5206
      +
      +Note that all SVN information has been stripped from the tarballs.  If you
      +need the SVN configuration, you should check out directly from SVN.  Revision
      +r5206 should equivalent to release 6.22 of NuttX 6.22:
      +
      +    svn checkout -r5206 svn://svn.code.sf.net/p/nuttx/code/trunk nuttx-code
      +
      +Or
      +
      +    svn checkout -r5206 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code
      +
      +Additional new features and extended functionality:
      +
      +    * RTOS: Application entry point is no longer user_start, but can be
      +      configured using CONFIG_USER_ENTRYPOINT.  NuttX now supports two work
      +      queues:  A lower priority work queue (for extended processing) and a
      +      higher priority work queue (for quick, high priority operations).
      +
      +    * Memory Management: Added a new granule-based allocated that can be
      +      used to manage, aligned and quantized DMA memory.
      +
      +    * File System: Add hooks to allocate I/O memory with and external
      +      allocated (need if required by DMA).
      +
      +    * Networking: ENC28J60 driver is (finally) verified.
      +
      +    * Drivers: Add hooks USB device drivers to allocate I/O memory with and
      +      external allocated (need if required by DMA).  Driver for the Windbond
      +      SPI FLASH family (W25x16, W25x32, W25x64, and others).  ADS7843E driver
      +      extended for TSC2046 and XPT2046 and verified.
      +
      +    * ARMv7-M: Added logic to reset the MCU using the NVIC.
      +
      +    * STM32: Add support for STM32F103VET6.
      +
      +    * STM32 Drivers: Add logic to re-initialize UARTs a second time to
      +      enable DMA (Mike Smith).  I2C driver error recovery (Mike Smith).
      +
      +    * STM32 boards: Support for USB host added add to several configurations
      +      (or at least explained in README files).  Support for the Shenzhou
      +      STM32F107 board (see www.armjishu.com).  Support for M3 Wildfire
      +      STM32F103 board (v2 and v3).
      +
      +    * Build System:  Kconfig string de-quoting logic.  Remove comments from
      +      defconfig files (Kate).  Add tool to create NuttX-style symbol tables.
      +      Numerous changes to configuration logic as needed for the new mconf-based
      +      configuration (much of this from Richard Cochran).  Refactor common
      +      Make.defs logic into tools/Config.mk (Richard Cochran).
      +
      +    * Library: Configurable terse output from strerror(). Added perror() (Kate).
      +      Add %n format to sscanf() (Kate).
      +
      +    * Applications: Numerous changes and extensions to the old uIP web server
      +      (from Kate and Max Holtzberg, see the ChangeLog for specific extensions).
      +      UDP network discovery utility (Max Holtzberg).  Embeddable Lightweight
      +      XML-RPC Server (http://www.drdobbs.com/web-development/an-embeddable-lightweight-xml-rpc-server/184405364, Max Holtzberg).
      +
      +Bugfixes (see the change log for details).  Some of these are very important
      +(marked *critical*):
      +
      +    * RTOS: Fixes to priority inheritance logic (*critical*).  waitpid()
      +      critical section.  Assertion in work_cancel() (Mike Smith).  mmap() (Kate).
      +
      +    * FAT File System: Improper Boolean expression caused un-necessary writes
      +      and performance issues (*critical*, Ronen Vainish).
      +
      +    * Networking: Remove an un-necessary delay from recvfrom().  This greatly
      +      improves network performance (*critical*, Max Holtzberg).
      +
      +    * Graphics: NX parameter checking errors.
      +
      +    * Drivers: Fix double release of memory in SDIO-based, MMC/SD driver
      +      (Ronen Vainish).
      +
      +    * LPC17xx:  Ethernet driver fixes needed for certain PHYs (Kate).
      +
      +    * AVR: Fix build error (Richard Cochran).
      +
      +    * STM32: USB OTG FS host driver NAKing an retries.  Power management
      +      compilation errors (Diego Sanchez).  Missing SPI3 remap logic.
      +
      +    * STM32 Drivers: Fix for Ethernet errata for STM32F107 (*critical*).
      +      Ethernet buffer alignment check.  Add "kludge" to Ethernet driver to
      +      handle DM9161 PHY which (at least on the Shenzhou board), sometimes
      +      does not come up correctly.
      +
      +    * Applications: THTTPD (Kate).  NSH ping when IP address is on a different
      +      network (Darcy Gong).
      +
      +    * Library: fread(), fflush(), fdopen(): Fix error handling logic (Ronen
      +      Vainish). Fix some field-width handling issues in sscanf()
      +
      +As well as other, less critical bugs (see the ChangeLog for details)
      -- 
      cgit v1.2.3
      
      
      From 96a334a758bbdc466ba8ae0cb20f2f79958623ec Mon Sep 17 00:00:00 2001
      From: patacongo 
      Date: Sat, 29 Sep 2012 20:34:25 +0000
      Subject: Implementation of /dev/random using the STM32 Random Number Generator
       (RNG)
      
      git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5207 42af7a65-404d-4744-a932-0658087f49c3
      ---
       nuttx/ChangeLog                           |   4 +
       nuttx/arch/arm/src/common/up_initialize.c |   6 +
       nuttx/arch/arm/src/common/up_internal.h   |   6 +
       nuttx/arch/arm/src/stm32/Kconfig          |   1 +
       nuttx/arch/arm/src/stm32/Make.defs        |   6 +-
       nuttx/arch/arm/src/stm32/chip/stm32_rng.h |  77 +++++++++
       nuttx/arch/arm/src/stm32/stm32_rng.c      | 264 ++++++++++++++++++++++++++++++
       nuttx/configs/stm3240g-eval/README.txt    |  11 +-
       nuttx/configs/stm3240g-eval/nsh/defconfig |   4 +-
       nuttx/configs/stm3240g-eval/src/Makefile  |   4 +-
       nuttx/drivers/Kconfig                     |   8 +
       11 files changed, 385 insertions(+), 6 deletions(-)
       create mode 100644 nuttx/arch/arm/src/stm32/chip/stm32_rng.h
       create mode 100644 nuttx/arch/arm/src/stm32/stm32_rng.c
      
      (limited to 'nuttx')
      
      diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
      index ef9e77132..55a06aeec 100644
      --- a/nuttx/ChangeLog
      +++ b/nuttx/ChangeLog
      @@ -3454,3 +3454,7 @@
       	  going outside of local network.  Submitted by Darcy Gong
       
       6.23 2012-09-29 Gregory Nutt 
      +
      +	* arch/arm/src/stm32/stm32_rng.c, chip/stm32_rng.h, and other files:
      +	  Implementation of /dev/random using the STM32 Random Number
      +	  Generator (RNG).
      diff --git a/nuttx/arch/arm/src/common/up_initialize.c b/nuttx/arch/arm/src/common/up_initialize.c
      index 094835c29..80f9b1193 100644
      --- a/nuttx/arch/arm/src/common/up_initialize.c
      +++ b/nuttx/arch/arm/src/common/up_initialize.c
      @@ -171,6 +171,12 @@ void up_initialize(void)
         ramlog_consoleinit();
       #endif
       
      +  /* Initialize the Random Number Generator (RNG)  */
      +
      +#ifdef CONFIG_DEV_RANDOM
      +  up_rnginitialize();
      +#endif
      +
         /* Initialize the system logging device */
       
       #ifdef CONFIG_SYSLOG_CHAR
      diff --git a/nuttx/arch/arm/src/common/up_internal.h b/nuttx/arch/arm/src/common/up_internal.h
      index 42142c5e8..0d3c5b1f2 100644
      --- a/nuttx/arch/arm/src/common/up_internal.h
      +++ b/nuttx/arch/arm/src/common/up_internal.h
      @@ -373,6 +373,12 @@ extern void up_usbuninitialize(void);
       # define up_usbuninitialize()
       #endif
       
      +/* Random Number Generator (RNG) ********************************************/
      +
      +#ifdef CONFIG_DEV_RANDOM
      +extern void up_rnginitialize(void);
      +#endif
      +
       /****************************************************************************
        * Name: up_check_stack
        *
      diff --git a/nuttx/arch/arm/src/stm32/Kconfig b/nuttx/arch/arm/src/stm32/Kconfig
      index fe89119a4..2f9100236 100644
      --- a/nuttx/arch/arm/src/stm32/Kconfig
      +++ b/nuttx/arch/arm/src/stm32/Kconfig
      @@ -320,6 +320,7 @@ config STM32_RNG
       	bool "RNG"
       	default n
       	depends on STM32_STM32F20XX || STM32_STM32F40XX
      +	select ARCH_HAVE_RNG
       
       config STM32_SDIO
       	bool "SDIO"
      diff --git a/nuttx/arch/arm/src/stm32/Make.defs b/nuttx/arch/arm/src/stm32/Make.defs
      index e52962977..ef14b48c1 100644
      --- a/nuttx/arch/arm/src/stm32/Make.defs
      +++ b/nuttx/arch/arm/src/stm32/Make.defs
      @@ -78,7 +78,7 @@ endif
       
       ifeq ($(CONFIG_USBHOST),y)
       ifeq ($(CONFIG_STM32_OTGFS),y)
      -CMN_CSRCS       += stm32_otgfshost.c
      +CMN_CSRCS	+= stm32_otgfshost.c
       endif
       endif
       
      @@ -119,6 +119,10 @@ ifeq ($(CONFIG_DAC),y)
       CHIP_CSRCS	+= stm32_dac.c
       endif
       
      +ifeq ($(CONFIG_DEV_RANDOM),y)
      +CHIP_CSRCS	+= stm32_rng.c
      +endif
      +
       ifeq ($(CONFIG_PWM),y)
       CHIP_CSRCS	+= stm32_pwm.c
       endif
      diff --git a/nuttx/arch/arm/src/stm32/chip/stm32_rng.h b/nuttx/arch/arm/src/stm32/chip/stm32_rng.h
      new file mode 100644
      index 000000000..5e31d5817
      --- /dev/null
      +++ b/nuttx/arch/arm/src/stm32/chip/stm32_rng.h
      @@ -0,0 +1,77 @@
      +/************************************************************************************
      + * arch/arm/src/stm32/chip/stm32_rng.h
      + *
      + *   Copyright (C) 2012 Max Holtzberg. All rights reserved.
      + *   Author: Max Holtzberg 
      + *
      + * 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_STC_STM32_CHIP_STM32_RNG_H
      +#define __ARCH_ARM_STC_STM32_CHIP_STM32_RNG_H
      +
      +/************************************************************************************
      + * Included Files
      + ************************************************************************************/
      +
      +#include 
      +#include "chip.h"
      +
      +/************************************************************************************
      + * Pre-processor Definitions
      + ************************************************************************************/
      +
      +/* Register Offsets *****************************************************************/
      +
      +#define STM32_RNG_CR_OFFSET       0x0000  /* RNG Control Register */
      +#define STM32_RNG_SR_OFFSET       0x0004  /* RNG Status Register */
      +#define STM32_RNG_DR_OFFSET       0x0008  /* RNG Data Register */
      +
      +/* Register Addresses ***************************************************************/
      +
      +#define STM32_RNG_CR              (STM32_RNG_BASE+STM32_RNG_CR_OFFSET)
      +#define STM32_RNG_SR              (STM32_RNG_BASE+STM32_RNG_SR_OFFSET)
      +#define STM32_RNG_DR              (STM32_RNG_BASE+STM32_RNG_DR_OFFSET)
      +
      +/* Register Bitfield Definitions ****************************************************/
      +
      +/* RNG Control Register */
      +
      +#define RNG_CR_RNGEN              (1 << 2)  /* Bit 2: RNG enable */
      +#define RNG_CR_IE                 (1 << 3)  /* Bit 3: Interrupt enable */
      +
      +/* RNG Status Register */
      +
      +#define RNG_SR_DRDY               (1 << 0) /* Bit 0: Data ready */
      +#define RNG_SR_CECS               (1 << 1) /* Bit 1: Clock error current status */
      +#define RNG_SR_SECS               (1 << 2) /* Bit 2: Seed error current status */
      +#define RNG_SR_CEIS               (1 << 5) /* Bit 5: Clock error interrupt status */
      +#define RNG_SR_SEIS               (1 << 6) /* Bit 6: Seed error interrupt status */
      +
      +#endif	/* __ARCH_ARM_STC_STM32_CHIP_STM32_RNG_H */
      diff --git a/nuttx/arch/arm/src/stm32/stm32_rng.c b/nuttx/arch/arm/src/stm32/stm32_rng.c
      new file mode 100644
      index 000000000..38e8108fe
      --- /dev/null
      +++ b/nuttx/arch/arm/src/stm32/stm32_rng.c
      @@ -0,0 +1,264 @@
      +/****************************************************************************
      + * arch/arm/src/stm32/stm32_rng.c
      + *
      + *   Copyright (C) 2012 Max Holtzberg. All rights reserved.
      + *   Author: Max Holtzberg 
      + *
      + * Redistribution and use in source and binary forms, with or without
      + * modification, are permitted provided that the following conditions
      + * are met:
      + *
      + * 1. Redistributions of source code must retain the above copyright
      + *    notice, this list of conditions and the following disclaimer.
      + * 2. Redistributions in binary form must reproduce the above copyright
      + *    notice, this list of conditions and the following disclaimer in
      + *    the documentation and/or other materials provided with the
      + *    distribution.
      + * 3. Neither the name NuttX nor the names of its contributors may be
      + *    used to endorse or promote products derived from this software
      + *    without specific prior written permission.
      + *
      + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
      + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
      + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
      + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
      + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
      + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
      + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
      + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
      + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
      + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
      + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
      + * POSSIBILITY OF SUCH DAMAGE.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +#include 
      +#include 
      +
      +#include "up_arch.h"
      +#include "chip/stm32_rng.h"
      +#include "up_internal.h"
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +static int stm32_rnginitialize(void);
      +static int stm32_interrupt(int irq, void *context);
      +static void stm32_enable(void);
      +static void stm32_disable(void);
      +static ssize_t stm32_read(struct file *filep, char *buffer, size_t);
      +
      +/****************************************************************************
      + * Private Types
      + ****************************************************************************/
      +
      +struct rng_dev_s
      +{
      +  sem_t rd_devsem;      /* Threads can only exclusively access the RNG */
      +  sem_t rd_readsem;     /* To block until the buffer is filled  */
      +  char *rd_buf;
      +  size_t rd_buflen;
      +  uint32_t rd_lastval;
      +  bool rd_first;
      +};
      +
      +/****************************************************************************
      + * Private Data
      + ****************************************************************************/
      +
      +static struct rng_dev_s g_rngdev;
      +
      +static const struct file_operations g_rngops =
      +{
      +  0,               /* open */
      +  0,               /* close */
      +  stm32_read,      /* read */
      +  0,               /* write */
      +  0,               /* seek */
      +  0                /* ioctl */
      +#ifndef CONFIG_DISABLE_POLL
      +  ,0               /* poll */
      +#endif
      +};
      +
      +/****************************************************************************
      + * Private functions
      + ****************************************************************************/
      +
      +static int stm32_rnginitialize()
      +{
      +  uint32_t regval;
      +
      +  vdbg("Initializing RNG\n");
      +
      +  memset(&g_rngdev, 0, sizeof(struct rng_dev_s));
      +
      +  sem_init(&g_rngdev.rd_devsem, 0, 1);
      +
      +  if (irq_attach(STM32_IRQ_RNG, stm32_interrupt))
      +    {
      +      /* We could not attach the ISR to the interrupt */
      +
      +      vdbg("Could not attach IRQ.\n");
      +
      +      return -EAGAIN;
      +    }
      +
      +  /* Enable interrupts */
      +
      +  regval = getreg32(STM32_RNG_CR);
      +  regval |=  RNG_CR_IE;
      +  putreg32(regval, STM32_RNG_CR);
      +
      +  up_enable_irq(STM32_IRQ_RNG);
      +
      +  return OK;
      +}
      +
      +static void stm32_enable()
      +{
      +  uint32_t regval;
      +
      +  g_rngdev.rd_first = true;
      +
      +  regval = getreg32(STM32_RNG_CR);
      +  regval |= RNG_CR_RNGEN;
      +  putreg32(regval, STM32_RNG_CR);
      +}
      +
      +static void stm32_disable()
      +{
      +  uint32_t regval;
      +  regval = getreg32(STM32_RNG_CR);
      +  regval &= ~RNG_CR_RNGEN;
      +  putreg32(regval, STM32_RNG_CR);
      +}
      +
      +static int stm32_interrupt(int irq, void *context)
      +{
      +  uint32_t rngsr;
      +  uint32_t data;
      +
      +  rngsr = getreg32(STM32_RNG_SR);
      +
      +  if ((rngsr & (RNG_SR_SEIS | RNG_SR_CEIS)) /* Check for error bits */
      +      || !(rngsr & RNG_SR_DRDY)) /* Data ready must be set */
      +    {
      +      /* This random value is not valid, we will try again. */
      +
      +      return OK;
      +    }
      +
      +  data = getreg32(STM32_RNG_DR);
      +
      +  /* As required by the FIPS PUB (Federal Information Processing Standard
      +   * Publication) 140-2, the first random number generated after setting the
      +   * RNGEN bit should not be used, but saved for comparison with the next
      +   * generated random number. Each subsequent generated random number has to be
      +   * compared with the previously generated number. The test fails if any two
      +   * compared numbers are equal (continuous random number generator test).
      +   */
      +
      +  if (g_rngdev.rd_first)
      +    {
      +      g_rngdev.rd_first = false;
      +      g_rngdev.rd_lastval = data;
      +      return OK;
      +    }
      +
      +  if (g_rngdev.rd_lastval == data)
      +    {
      +      /* Two subsequent same numbers, we will try again. */
      +
      +      return OK;
      +    }
      +
      +  /* If we get here, the random number is valid. */
      +
      +  g_rngdev.rd_lastval = data;
      +
      +  if (g_rngdev.rd_buflen >= 4)
      +    {
      +      g_rngdev.rd_buflen -= 4;
      +      *(uint32_t*)&g_rngdev.rd_buf[g_rngdev.rd_buflen] = data;
      +    }
      +  else
      +    {
      +      while (g_rngdev.rd_buflen > 0)
      +        {
      +          g_rngdev.rd_buf[--g_rngdev.rd_buflen] = (char)data;
      +          data >>= 8;
      +        }
      +    }
      +
      +  if (g_rngdev.rd_buflen == 0)
      +    {
      +      /* Buffer filled, stop further interrupts. */
      +
      +      stm32_disable();
      +      sem_post(&g_rngdev.rd_readsem);
      +    }
      +
      +  return OK;
      +}
      +
      +/****************************************************************************
      + * Name: stm32_read
      + ****************************************************************************/
      +
      +static ssize_t stm32_read(struct file *filep, char *buffer, size_t buflen)
      +{
      +  if (sem_wait(&g_rngdev.rd_devsem) != OK)
      +    {
      +      return -errno;
      +    }
      +  else
      +    {
      +      /* We've got the semaphore. */
      +
      +      /* Initialize semaphore with 0 for blocking until the buffer is filled from
      +       * interrupts.
      +       */
      +
      +      sem_init(&g_rngdev.rd_readsem, 0, 1);
      +
      +      g_rngdev.rd_buflen = buflen;
      +      g_rngdev.rd_buf = buffer;
      +
      +      /* Enable RNG with interrupts */
      +
      +      stm32_enable();
      +
      +      /* Wait until the buffer is filled */
      +
      +      sem_wait(&g_rngdev.rd_readsem);
      +
      +      /* Free RNG for next use */
      +
      +      sem_post(&g_rngdev.rd_devsem);
      +
      +      return buflen;
      +    }
      +}
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +void up_rnginitialize()
      +{
      +  stm32_rnginitialize();
      +  register_driver("/dev/random", &g_rngops, 0444, NULL);
      +}
      diff --git a/nuttx/configs/stm3240g-eval/README.txt b/nuttx/configs/stm3240g-eval/README.txt
      index df98f087d..b536097a8 100644
      --- a/nuttx/configs/stm3240g-eval/README.txt
      +++ b/nuttx/configs/stm3240g-eval/README.txt
      @@ -1110,7 +1110,16 @@ Where  is one of the following:
       
              nsh> umount /mnt/stuff
       
      -    11. This configuration requires that jumper JP22 be set to enable RS-232
      +    11. By default, this configuration supports /dev/random using the STM32's
      +        RNG hardware.  This can be disabled as follows:
      +
      +        -CONFIG_STM32_RNG=y
      +        +CONFIG_STM32_RNG=n
      + 
      +        -CONFIG_DEV_RANDOM=y
      +        +CONFIG_DEV_RANDOM=n
      +
      +    12. This configuration requires that jumper JP22 be set to enable RS-232
              operation.
       
         nsh2:
      diff --git a/nuttx/configs/stm3240g-eval/nsh/defconfig b/nuttx/configs/stm3240g-eval/nsh/defconfig
      index 80f5ec167..653538b45 100644
      --- a/nuttx/configs/stm3240g-eval/nsh/defconfig
      +++ b/nuttx/configs/stm3240g-eval/nsh/defconfig
      @@ -69,7 +69,6 @@ CONFIG_STM32_BUILDROOT=n
       #
       # JTAG Enable settings (by default JTAG-DP and SW-DP are disabled):
       #
      -CONFIG_STM32_DFU=y
       CONFIG_STM32_JTAG_FULL_ENABLE=y
       CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n
       CONFIG_STM32_JTAG_SW_ENABLE=n
      @@ -100,7 +99,7 @@ CONFIG_STM32_OTGHS=n
       CONFIG_STM32_DCMI=n
       CONFIG_STM32_CRYP=n
       CONFIG_STM32_HASH=n
      -CONFIG_STM32_RNG=n
      +CONFIG_STM32_RNG=y
       CONFIG_STM32_OTGFS=n
       # AHB3:
       CONFIG_STM32_FSMC=n
      @@ -306,6 +305,7 @@ CONFIG_SCHED_WORKSTACKSIZE=2048
       CONFIG_SIG_SIGWORK=4
       CONFIG_SCHED_WAITPID=y
       CONFIG_SCHED_ATEXIT=n
      +CONFIG_DEV_RANDOM=y
       
       #
       # System Logging
      diff --git a/nuttx/configs/stm3240g-eval/src/Makefile b/nuttx/configs/stm3240g-eval/src/Makefile
      index 80225ea1f..ffcf719ab 100644
      --- a/nuttx/configs/stm3240g-eval/src/Makefile
      +++ b/nuttx/configs/stm3240g-eval/src/Makefile
      @@ -100,8 +100,8 @@ OBJS		= $(AOBJS) $(COBJS)
       ARCH_SRCDIR	= $(TOPDIR)/arch/$(CONFIG_ARCH)/src
       ifeq ($(WINTOOL),y)
         CFLAGS	+= -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \
      -  		   -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
      -  		   -I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}"
      +			   -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
      +			   -I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}"
       else
         CFLAGS	+= -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m
       endif
      diff --git a/nuttx/drivers/Kconfig b/nuttx/drivers/Kconfig
      index ea218a592..1d263ec14 100644
      --- a/nuttx/drivers/Kconfig
      +++ b/nuttx/drivers/Kconfig
      @@ -11,6 +11,14 @@ config DEV_ZERO
       	bool "Enable /dev/zero"
       	default n
       
      +config ARCH_HAVE_RNG
      +	bool
      +
      +config DEV_RANDOM 
      +	bool "Enable /dev/random"
      +	default n
      +	depends on ARCH_HAVE_RNG
      +
       config LOOP
       	bool "Enable loop device"
       	default n
      -- 
      cgit v1.2.3
      
      
      From 14b3f41aa6613f94616d7d6bcba5454c7f8caf8a Mon Sep 17 00:00:00 2001
      From: patacongo 
      Date: Wed, 3 Oct 2012 23:36:54 +0000
      Subject: Delete the apps/vsn directory (moved commands to apps/system)
      
      git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5208 42af7a65-404d-4744-a932-0658087f49c3
      ---
       apps/ChangeLog.txt              |   3 +
       apps/Kconfig                    |   4 -
       apps/Makefile                   |   3 +-
       apps/README.txt                 |   2 +-
       apps/system/Kconfig             |  20 +-
       apps/system/Make.defs           |  17 ++
       apps/system/Makefile            |   2 +-
       apps/system/free/free.c         |  80 +++---
       apps/system/install/install.c   | 606 ++++++++++++++++++++++------------------
       apps/system/poweroff/Kconfig    |  16 ++
       apps/system/poweroff/Makefile   | 114 ++++++++
       apps/system/poweroff/README.txt |   5 +
       apps/system/poweroff/poweroff.c |  63 +++++
       apps/system/ramtron/Kconfig     |  14 +
       apps/system/ramtron/Makefile    | 114 ++++++++
       apps/system/ramtron/README.txt  |   7 +
       apps/system/ramtron/ramtron.c   | 104 +++++++
       apps/system/sdcard/Kconfig      |  14 +
       apps/system/sdcard/Makefile     | 114 ++++++++
       apps/system/sdcard/README.txt   |   7 +
       apps/system/sdcard/sdcard.c     | 161 +++++++++++
       apps/system/sysinfo/Kconfig     |  13 +
       apps/system/sysinfo/Makefile    | 114 ++++++++
       apps/system/sysinfo/README.txt  |   6 +
       apps/system/sysinfo/sysinfo.c   |  69 +++++
       apps/vsn/Kconfig                |  11 -
       apps/vsn/Make.defs              |  51 ----
       apps/vsn/Makefile               |  71 -----
       apps/vsn/poweroff/Kconfig       |  14 -
       apps/vsn/poweroff/Makefile      | 114 --------
       apps/vsn/poweroff/README.txt    |   5 -
       apps/vsn/poweroff/poweroff.c    |  54 ----
       apps/vsn/ramtron/Kconfig        |  14 -
       apps/vsn/ramtron/Makefile       | 114 --------
       apps/vsn/ramtron/README.txt     |   7 -
       apps/vsn/ramtron/ramtron.c      |  99 -------
       apps/vsn/sdcard/Kconfig         |  14 -
       apps/vsn/sdcard/Makefile        | 114 --------
       apps/vsn/sdcard/README.txt      |   7 -
       apps/vsn/sdcard/sdcard.c        | 134 ---------
       apps/vsn/sysinfo/Kconfig        |  14 -
       apps/vsn/sysinfo/Makefile       | 114 --------
       apps/vsn/sysinfo/README.txt     |   6 -
       apps/vsn/sysinfo/sysinfo.c      |  69 -----
       nuttx/Documentation/NuttX.html  |   2 +-
       45 files changed, 1353 insertions(+), 1347 deletions(-)
       create mode 100644 apps/system/poweroff/Kconfig
       create mode 100644 apps/system/poweroff/Makefile
       create mode 100644 apps/system/poweroff/README.txt
       create mode 100644 apps/system/poweroff/poweroff.c
       create mode 100644 apps/system/ramtron/Kconfig
       create mode 100644 apps/system/ramtron/Makefile
       create mode 100644 apps/system/ramtron/README.txt
       create mode 100644 apps/system/ramtron/ramtron.c
       create mode 100644 apps/system/sdcard/Kconfig
       create mode 100644 apps/system/sdcard/Makefile
       create mode 100644 apps/system/sdcard/README.txt
       create mode 100644 apps/system/sdcard/sdcard.c
       create mode 100644 apps/system/sysinfo/Kconfig
       create mode 100644 apps/system/sysinfo/Makefile
       create mode 100644 apps/system/sysinfo/README.txt
       create mode 100644 apps/system/sysinfo/sysinfo.c
       delete mode 100644 apps/vsn/Kconfig
       delete mode 100644 apps/vsn/Make.defs
       delete mode 100644 apps/vsn/Makefile
       delete mode 100644 apps/vsn/poweroff/Kconfig
       delete mode 100644 apps/vsn/poweroff/Makefile
       delete mode 100644 apps/vsn/poweroff/README.txt
       delete mode 100644 apps/vsn/poweroff/poweroff.c
       delete mode 100644 apps/vsn/ramtron/Kconfig
       delete mode 100644 apps/vsn/ramtron/Makefile
       delete mode 100644 apps/vsn/ramtron/README.txt
       delete mode 100644 apps/vsn/ramtron/ramtron.c
       delete mode 100644 apps/vsn/sdcard/Kconfig
       delete mode 100644 apps/vsn/sdcard/Makefile
       delete mode 100644 apps/vsn/sdcard/README.txt
       delete mode 100644 apps/vsn/sdcard/sdcard.c
       delete mode 100644 apps/vsn/sysinfo/Kconfig
       delete mode 100644 apps/vsn/sysinfo/Makefile
       delete mode 100644 apps/vsn/sysinfo/README.txt
       delete mode 100644 apps/vsn/sysinfo/sysinfo.c
      
      (limited to 'nuttx')
      
      diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt
      index 75f02754b..2d7b2eb9f 100644
      --- a/apps/ChangeLog.txt
      +++ b/apps/ChangeLog.txt
      @@ -350,3 +350,6 @@
       	  feature of the NxWidgets/NxWM unit tests.
       
       6.23 2012-xx-xx Gregory Nutt 
      +
      +	* vsn: Moved all NSH commands from vsn/ to system/.  Deleted the vsn/
      +	  directory.
      diff --git a/apps/Kconfig b/apps/Kconfig
      index 5543ba72d..ea9bd2d31 100644
      --- a/apps/Kconfig
      +++ b/apps/Kconfig
      @@ -34,7 +34,3 @@ endmenu
       menu "System NSH Add-Ons"
       source "$APPSDIR/system/Kconfig"
       endmenu
      -
      -menu "VSN board Add-Ons"
      -source "$APPSDIR/vsn/Kconfig"
      -endmenu
      diff --git a/apps/Makefile b/apps/Makefile
      index 3a59fd6b4..d2b0ecdab 100644
      --- a/apps/Makefile
      +++ b/apps/Makefile
      @@ -49,7 +49,7 @@ APPDIR = ${shell pwd}
       #   list can be extended by the .config file as well
       
       CONFIGURED_APPS =
      -SUBDIRS = examples graphics interpreters modbus namedapp nshlib netutils system vsn
      +SUBDIRS = examples graphics interpreters modbus namedapp nshlib netutils system
       
       # There are two different mechanisms for obtaining the list of configured
       # directories:
      @@ -78,7 +78,6 @@ include namedapp/Make.defs
       include netutils/Make.defs
       include nshlib/Make.defs
       include system/Make.defs
      -include vsn/Make.defs
       
       # INSTALLED_APPS is the list of currently available application directories.  It
       # is the same as CONFIGURED_APPS, but filtered to exclude any non-existent
      diff --git a/apps/README.txt b/apps/README.txt
      index f9c9ececd..7a379254e 100644
      --- a/apps/README.txt
      +++ b/apps/README.txt
      @@ -107,7 +107,7 @@ NuttX is configured.  .config is included in the toplevel apps/Makefile.
       As a minimum, this configuration file must define files to add to the
       CONFIGURED_APPS list like:
       
      -  CONFIGURED_APPS  += examples/hello vsn/poweroff
      +  CONFIGURED_APPS  += examples/hello system/poweroff
       
       Named Start-Up main() function
       ------------------------------
      diff --git a/apps/system/Kconfig b/apps/system/Kconfig
      index 44bf5a2e6..d4d434665 100644
      --- a/apps/system/Kconfig
      +++ b/apps/system/Kconfig
      @@ -3,7 +3,7 @@
       # see misc/tools/kconfig-language.txt.
       #
       
      -menu "Custom free memory command"
      +menu "Custom Free Memory Command"
       source "$APPSDIR/system/free/Kconfig"
       endmenu
       
      @@ -15,6 +15,22 @@ menu "FLASH Program Installation"
       source "$APPSDIR/system/install/Kconfig"
       endmenu
       
      -menu "readline() support"
      +menu "readline()"
       source "$APPSDIR/system/readline/Kconfig"
       endmenu
      +
      +menu "Power Off"
      +source "$APPSDIR/system/poweroff/Kconfig"
      +endmenu
      +
      +menu "RAMTRON"
      +source "$APPSDIR/system/ramtron/Kconfig"
      +endmenu
      +
      +menu "SD Card"
      +source "$APPSDIR/system/sdcard/Kconfig"
      +endmenu
      +
      +menu "Sysinfo"
      +source "$APPSDIR/system/sysinfo/Kconfig"
      +endmenu
      diff --git a/apps/system/Make.defs b/apps/system/Make.defs
      index a4aea2d31..3d10f84e5 100644
      --- a/apps/system/Make.defs
      +++ b/apps/system/Make.defs
      @@ -49,3 +49,20 @@ endif
       ifeq ($(CONFIG_SYSTEM_READLINE),y)
       CONFIGURED_APPS += system/readline
       endif
      +
      +ifeq ($(CONFIG_SYSTEM_POWEROFF),y)
      +CONFIGURED_APPS += system/poweroff
      +endif
      +
      +ifeq ($(CONFIG_SYSTEM_RAMTRON),y)
      +CONFIGURED_APPS += system/ramtron
      +endif
      +
      +ifeq ($(CONFIG_SYSTEM_SDCARD),y)
      +CONFIGURED_APPS += system/sdcard
      +endif
      +
      +ifeq ($(CONFIG_SYSTEM_SYSINFO),y)
      +CONFIGURED_APPS += system/sysinfo
      +endif
      +
      diff --git a/apps/system/Makefile b/apps/system/Makefile
      index 73eb60d15..d64bb54c6 100644
      --- a/apps/system/Makefile
      +++ b/apps/system/Makefile
      @@ -37,7 +37,7 @@
       
       # Sub-directories containing system task
       
      -SUBDIRS = free i2c install readline
      +SUBDIRS = free i2c install readline poweroff ramtron sdcard sysinfo
       
       # Create the list of installed runtime modules (INSTALLED_DIRS)
       
      diff --git a/apps/system/free/free.c b/apps/system/free/free.c
      index 3d9698ecb..c44cd5e22 100644
      --- a/apps/system/free/free.c
      +++ b/apps/system/free/free.c
      @@ -33,57 +33,65 @@
        *
        ****************************************************************************/
       
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
       #include 
       #include 
       
       #include 
       #include 
       
      -
       /****************************************************************************
        * Private Functions
        ****************************************************************************/
      - 
      -/* \todo Max block size only works on uniform prog mem */
      - 
      -void free_getprogmeminfo(struct mallinfo * mem)
      +
      +/* TODO Max block size only works on uniform prog mem */
      +
      +static void free_getprogmeminfo(struct mallinfo * mem)
       {
      -    uint16_t page = 0, stpage = 0xFFFF;
      -    uint16_t pagesize = 0;
      -    int status;
      -    
      -    mem->arena    = 0;
      -    mem->fordblks = 0;
      -    mem->uordblks = 0;
      -    mem->mxordblk = 0;
      -    
      -    for (status=0, page=0; status >= 0; page++) {
      -    
      -        status = up_progmem_ispageerased(page);
      -        pagesize = up_progmem_pagesize(page);
      -        
      -        mem->arena += pagesize;
      -        
      -        /* Is this beginning of new free space section */
      -        if (status == 0) {
      -            if (stpage == 0xFFFF) stpage = page;
      -            mem->fordblks += pagesize;
      +  uint16_t page = 0, stpage = 0xFFFF;
      +  uint16_t pagesize = 0;
      +  int status;
      +
      +  mem->arena    = 0;
      +  mem->fordblks = 0;
      +  mem->uordblks = 0;
      +  mem->mxordblk = 0;
      +
      +  for (status=0, page=0; status >= 0; page++)
      +    {
      +      status = up_progmem_ispageerased(page);
      +      pagesize = up_progmem_pagesize(page);
      +
      +      mem->arena += pagesize;
      +
      +      /* Is this beginning of new free space section */
      +
      +      if (status == 0)
      +        {
      +          if (stpage == 0xFFFF) stpage = page;
      +          mem->fordblks += pagesize;
               }
      -        else if (status != 0) {
      -            mem->uordblks += pagesize;
      -
      -            if (stpage != 0xFFFF && up_progmem_isuniform()) {
      -                stpage = page - stpage;
      -                if (stpage > mem->mxordblk) 
      -                    mem->mxordblk = stpage;
      -                stpage = 0xFFFF;
      +      else if (status != 0)
      +        {
      +          mem->uordblks += pagesize;
      +
      +          if (stpage != 0xFFFF && up_progmem_isuniform())
      +            {
      +              stpage = page - stpage;
      +              if (stpage > mem->mxordblk)
      +                {
      +                  mem->mxordblk = stpage;
      +                }
      +              stpage = 0xFFFF;
                   }
               }
           }
      -    
      -    mem->mxordblk *= pagesize;
      -}
       
      +  mem->mxordblk *= pagesize;
      +}
       
       /****************************************************************************
        * Public Functions
      diff --git a/apps/system/install/install.c b/apps/system/install/install.c
      index 2f11c6434..fd14b7a6f 100644
      --- a/apps/system/install/install.c
      +++ b/apps/system/install/install.c
      @@ -33,6 +33,10 @@
        *
        ****************************************************************************/
       
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
       #include 
       #include 
       #include 
      @@ -43,9 +47,8 @@
       #include 
       #include 
       
      -
       /****************************************************************************
      - * Definitions
      + * Pre-processor Definitions
        ****************************************************************************/
       
       #define ACTION_INSTALL              0x01
      @@ -55,12 +58,11 @@
       
       #define INSTALL_PROGRAMBLOCKSIZE    1024
       
      -
       /****************************************************************************
        * Private data
        ****************************************************************************/
       
      -const char *install_help = 
      +static const char *install_help =
           "Installs XIP program into flash and creates a start-up script in the\n"
           "destination directory.\n\n"
           "Usage:\t%s [options] source-file.xip destination-directory\n\n"
      @@ -72,341 +74,397 @@ const char *install_help =
           "\t--force\t\t\tReplaces existing installation\n"
           "\t--start \t\tInstalls application at or after \n"
           "\t--margin \tLeave some free space after the kernel (default 16)\n";
      -    
      -const char *install_script_text = 
      +
      +static const char *install_script_text =
           "# XIP stacksize=%x priority=%x size=%x\n";
      -    
      -const char *install_script_exec = 
      +
      +static const char *install_script_exec =
           "exec 0x%x\n";
      -    
      -    
      +
       /****************************************************************************
        * Private functions
        ****************************************************************************/
       
      -int install_getstartpage(int startpage, int pagemargin, int desiredsize)
      +static int install_getstartpage(int startpage, int pagemargin, int desiredsize)
       {
      -    uint16_t page = 0, stpage = 0xFFFF;
      -    uint16_t pagesize = 0;
      -    int      maxlen = -1;
      -    int      maxlen_start = 0xFFFF;
      -    int      status;
      -    
      -    for (status=0, page=0; status >= 0; page++) {
      -    
      -        status   = up_progmem_ispageerased(page);
      -        pagesize = up_progmem_pagesize(page);
      -        
      -        /* Is this beginning of new free space section */
      -        if (status == 0) {
      -            if (stpage == 0xFFFF) stpage = page;
      +  uint16_t page = 0, stpage = 0xffff;
      +  uint16_t pagesize = 0;
      +  int      maxlen = -1;
      +  int      maxlen_start = 0xffff;
      +  int      status;
      +
      +  for (status=0, page=0; status >= 0; page++)
      +    {
      +      status   = up_progmem_ispageerased(page);
      +      pagesize = up_progmem_pagesize(page);
      +
      +      /* Is this beginning of new free space section */
      +
      +      if (status == 0)
      +        {
      +          if (stpage == 0xffff) stpage = page;
               }
      -        else if (status != 0) {
      -
      -            if (stpage != 0xFFFF) {
      -                
      -                if ( (page - stpage) > maxlen) {
      +      else if (status != 0)
      +        {
      +          if (stpage != 0xffff)
      +            {
      +              if ((page - stpage) > maxlen)
      +                {
      +                  if (maxlen==-1)
      +                    {
      +                      /* First time found sth? */
      +
      +                      stpage += pagemargin;
      +                      maxlen = 0;
      +                    }
       
      -                    if (maxlen==-1) { /* First time found sth? */
      -                        stpage += pagemargin;
      -                        maxlen = 0;
      +                  if(stpage < startpage)
      +                    {
      +                      stpage = startpage;
                           }
      -                    
      -                    if(stpage < startpage)
      -                        stpage = startpage;
      -                    
      -                    if (page > stpage) {
      -                        maxlen = page - stpage;
      -                        maxlen_start = stpage;
      +
      +                  if (page > stpage)
      +                    {
      +                      maxlen = page - stpage;
      +                      maxlen_start = stpage;
                           }
      -                    
      -                    if (maxlen*pagesize >= desiredsize) {
      -                        /* printf("Found page at %d ... %d\n", stpage, page); */
      -                        return maxlen_start*pagesize;
      +
      +                  if (maxlen*pagesize >= desiredsize)
      +                    {
      +                      /* printf("Found page at %d ... %d\n", stpage, page); */
      +                      return maxlen_start*pagesize;
                           }
                       }
      -                
      -                stpage = 0xFFFF;
      +
      +              stpage = 0xffff;
                   }
               }
           }
      -    
      -    /* Requested space is not available */
      -    
      -    return -1;
      -}
       
      +  /* Requested space is not available */
      +
      +  return -1;
      +}
       
      -int install_programflash(int startaddr, const char *source)
      +static int install_programflash(int startaddr, const char *source)
       {
      -    int  status;
      -    int  count;
      -    int  totalsize = 0;
      -    char *buf;
      -    FILE *fp;
      -    
      -    if ( (buf = malloc(INSTALL_PROGRAMBLOCKSIZE)) == NULL )
      -        return -errno;
      -    
      -    if ( (fp=fopen(source, "r")) ) {
      -        do {
      -            count = fread(buf, 1, INSTALL_PROGRAMBLOCKSIZE, fp);
      -    
      -            if ( (status = up_progmem_write(startaddr, buf, count)) < 0) {
      -                totalsize = status;
      -                break;
      +  int  status;
      +  int  count;
      +  int  totalsize = 0;
      +  char *buf;
      +  FILE *fp;
      +
      +  if ((buf = malloc(INSTALL_PROGRAMBLOCKSIZE)) == NULL)
      +    {
      +      return -ENOMEM;
      +    }
      +
      +  if ((fp = fopen(source, "r")))
      +    {
      +      do
      +        {
      +          count = fread(buf, 1, INSTALL_PROGRAMBLOCKSIZE, fp);
      +
      +          if ((status = up_progmem_write(startaddr, buf, count)) < 0)
      +            {
      +              totalsize = status;
      +              break;
                   }
      -                
      -            startaddr += count;
      -            totalsize += count;
      +
      +          startaddr += count;
      +          totalsize += count;
               }
      -        while(count);
      +      while(count);
      +    }
      +  else
      +    {
      +      totalsize = -errno;
           }
      -    else totalsize = -errno;
      -            
      -    fclose(fp);
      -    free(buf);
      -    
      -    return totalsize;
      -}
       
      +  fclose(fp);
      +  free(buf);
       
      -void install_getscriptname(char *scriptname, const char *progname, const char *destdir)
      -{
      -    const char * progonly;
      -
      -    /* I.e. as /usr/bin */
      -    strcpy(scriptname, destdir);
      -    
      -    /* extract from i.e. /sdcard/demo -> /demo, together with / */
      -    progonly = strrchr(progname, '/');
      -    strcat(scriptname, progonly);
      +  return totalsize;
       }
       
      -
      -int install_getprogsize(const char *progname)
      +static void install_getscriptname(char *scriptname, const char *progname, const char *destdir)
       {
      -    struct stat fileinfo;
      -    
      -    if ( stat(progname, &fileinfo) < 0 ) 
      -        return -1;
      -        
      -    return fileinfo.st_size;
      +  const char * progonly;
      +
      +  /* I.e. as /usr/bin */
      +
      +  strcpy(scriptname, destdir);
      +
      +  /* extract from i.e. /sdcard/demo -> /demo, together with / */
      +
      +  progonly = strrchr(progname, '/');
      +  strcat(scriptname, progonly);
       }
       
      +static int install_getprogsize(const char *progname)
      +{
      +  struct stat fileinfo;
      +
      +  if (stat(progname, &fileinfo) < 0)
      +    {
      +      return -1;
      +    }
      +
      +  return fileinfo.st_size;
      +}
       
      -int install_alreadyexists(const char *scriptname)
      +static int install_alreadyexists(const char *scriptname)
       {
      -    FILE *fp;
      -    
      -    if ( (fp=fopen(scriptname, "r"))==NULL )
      -        return 0;
      -        
      -    fclose(fp);
      +  FILE *fp;
      +
      +  if ((fp = fopen(scriptname, "r")) == NULL)
      +    {
      +      return 0;
      +    }
      +
      +  fclose(fp);
           return 1;
       }
       
      -
      -int install_createscript(int addr, int stacksize, int progsize, 
      -        int priority, const char *scriptname)
      +static int install_createscript(int addr, int stacksize, int progsize,
      +                                int priority, const char *scriptname)
       {
      -    FILE *fp;
      -    
      -    if ( (fp=fopen(scriptname, "w+"))==NULL )
      -        return -errno;
      -        
      -    fprintf(fp, install_script_text, stacksize, priority, progsize);
      -    fprintf(fp, install_script_exec, addr);
      -    
      -    fflush(fp);
      -    fclose(fp);
      -
      -    return 0;
      -}
      +  FILE *fp;
      +
      +  if ((fp = fopen(scriptname, "w+")) == NULL)
      +    {
      +      return -errno;
      +    }
       
      +  fprintf(fp, install_script_text, stacksize, priority, progsize);
      +  fprintf(fp, install_script_exec, addr);
       
      -int install_getlasthexvalue(FILE *fp, char delimiter)
      +  fflush(fp);
      +  fclose(fp);
      +
      +  return 0;
      +}
      +
      +static int install_getlasthexvalue(FILE *fp, char delimiter)
       {
      -    char buf[128];
      -    char *p;
      -    
      -    if (fgets(buf, 127, fp)) {
      -        if ( (p = strrchr(buf, delimiter)) ) {
      -            return strtol(p+1, NULL, 16);
      +  char buf[128];
      +  char *p;
      +
      +  if (fgets(buf, 127, fp))
      +    {
      +      if ((p = strrchr(buf, delimiter)))
      +        {
      +          return strtol(p+1, NULL, 16);
               }
           }
      -    return -1;
      -}
       
      +  return -1;
      +}
       
      -int install_remove(const char *scriptname)
      +static int install_remove(const char *scriptname)
       {
      -    FILE    *fp;
      -    int      progsize, addr, freedsize;
      -    uint16_t page;
      -    int      status = 0;
      -    
      -    /* Parse script */
      -    
      -    if ( (fp=fopen(scriptname, "r")) ) {
      -        progsize  = install_getlasthexvalue(fp,'=');
      -        addr      = install_getlasthexvalue(fp,' ');
      -        freedsize = progsize;
      +  FILE    *fp;
      +  int      progsize, addr, freedsize;
      +  uint16_t page;
      +  int      status = 0;
      +
      +  /* Parse script */
      +
      +  if ((fp = fopen(scriptname, "r")))
      +    {
      +      progsize  = install_getlasthexvalue(fp,'=');
      +      addr      = install_getlasthexvalue(fp,' ');
      +      freedsize = progsize;
      +    }
      +  else
      +    {
      +      return -errno;
      +    }
      +
      +  fclose(fp);
      +
      +  /* Remove pages */
      +
      +  if (progsize <= 0 || addr <= 0)
      +    {
      +      return -EIO;
           }
      -    else return -errno;
      -            
      -    fclose(fp);
      -    
      -    /* Remove pages */
      -    
      -    if (progsize <= 0 || addr <= 0)
      -        return -EIO;
      -        
      -    do {
      -        if ((page = up_progmem_getpage(addr)) < 0) {
      -            status = -page;
      -            break;
      +
      +  do
      +    {
      +      if ((page = up_progmem_getpage(addr)) < 0)
      +        {
      +          status = -page;
      +          break;
               }
      -        
      -        if ( up_progmem_erasepage(page) < 0) {
      -            status = -page;
      -            break;
      +
      +      if (up_progmem_erasepage(page) < 0)
      +        {
      +          status = -page;
      +          break;
               }
      -        
      -        addr += up_progmem_pagesize(page);
      -        progsize -= up_progmem_pagesize(page);
      -        
      -    } while(progsize > 0);
      -    
      -    if (status < 0) return status;
      -    
      -    /* Remove script file */
      -    
      -    if (unlink(scriptname) < 0) return -errno;
      -    
      -    return freedsize;
      +
      +      addr += up_progmem_pagesize(page);
      +      progsize -= up_progmem_pagesize(page);
      +
      +    }
      +  while(progsize > 0);
      +
      +  if (status < 0)
      +    {
      +      return status;
      +    }
      +
      +  /* Remove script file */
      +
      +  if (unlink(scriptname) < 0)
      +    {
      +      return -errno;
      +    }
      +
      +  return freedsize;
       }
       
       
       /****************************************************************************
      - * Start
      + * Public Functions
        ****************************************************************************/
       
       int install_main(int argc, char *argv[])
       {
      -    int i;
      -    int progsize;
      -    int scrsta;
      -    int stacksize       = 4096;
      -    int priority        = SCHED_PRIORITY_DEFAULT;
      -    int pagemargin      = 16;
      -    int startpage       = 0;
      -    int startaddr       = 0;
      -    int action          = ACTION_INSTALL;
      -    char scriptname[128];
      -    
      -    /* Supported? */
      -    
      -    if ( !up_progmem_isuniform() ) {
      -        fprintf(stderr, "Error: install supports uniform organization only.\n");
      -        return -1;
      +  int i;
      +  int progsize;
      +  int scrsta;
      +  int stacksize       = 4096;
      +  int priority        = SCHED_PRIORITY_DEFAULT;
      +  int pagemargin      = 16;
      +  int startpage       = 0;
      +  int startaddr       = 0;
      +  int action          = ACTION_INSTALL;
      +  char scriptname[128];
      +
      +  /* Supported? */
      +
      +  if (!up_progmem_isuniform())
      +    {
      +      fprintf(stderr, "Error: install supports uniform organization only.\n");
      +      return -1;
           }
      -    
      -    /* Parse arguments */
      -    
      -    for (i=1; i argc-1) {
      -                action = ACTION_INSUFPARAM;
      -                break;  /* are there sufficient parameters */
      -            }
      -            if ( (scrsta=install_remove(argv[i])) < 0) {
      -                fprintf(stderr, "Could not remove program: %s\n", strerror(-scrsta) );
      +
      +  /* Do the job */
      +
      +  switch(action & 1)
      +    {
      +      case ACTION_REMOVE:
      +        if (i > argc-1)
      +          {
      +            action = ACTION_INSUFPARAM;
      +            break;  /* are there sufficient parameters */
      +          }
      +
      +        if ((scrsta=install_remove(argv[i])) < 0)
      +          {
      +            fprintf(stderr, "Could not remove program: %s\n", strerror(-scrsta));
      +            return -1;
      +          }
      +
      +        printf("Removed %s and freed %d bytes\n", argv[i], scrsta);
      +          return 0;
      +
      +      case ACTION_INSTALL:
      +        if (i > argc-2)
      +          {
      +            action = ACTION_INSUFPARAM;
      +            break;  /* are there sufficient parameters */
      +          }
      +
      +        install_getscriptname(scriptname, argv[i], argv[i+1]);
      +
      +        /* script-exists? */
      +
      +        if (install_alreadyexists(scriptname) == 1)
      +          {
      +            if (action != ACTION_REINSTALL)
      +              {
      +                fprintf(stderr, "Program with that name already exists.\n");
      +                return -EEXIST;
      +              }
      +
      +            if ((scrsta = install_remove(scriptname)) < 0)
      +              {
      +                fprintf(stderr, "Could not remove program: %s\n", strerror(-scrsta));
                       return -1;
      -            }
      -            printf("Removed %s and freed %d bytes\n", argv[i], scrsta);
      -            return 0;
      -            
      -    
      -        case ACTION_INSTALL:
      -            if (i > argc-2) {
      -                action = ACTION_INSUFPARAM;
      -                break;  /* are there sufficient parameters */
      -            }
      -            
      -            install_getscriptname(scriptname, argv[i], argv[i+1]);
      -            
      -            // script-exists?
      -            if (install_alreadyexists(scriptname)==1) {
      -                
      -                if (action != ACTION_REINSTALL) {
      -                    fprintf(stderr, "Program with that name already exists.\n");
      -                    return -EEXIST;
      -                }
      -                
      -                if ( (scrsta=install_remove(scriptname)) < 0) {
      -                    fprintf(stderr, "Could not remove program: %s\n", strerror(-scrsta) );
      -                    return -1;
      -                }
      -                
      -                printf("Replacing %s\n", scriptname);
      -            }
      -            
      -            startaddr = install_getstartpage(startpage, pagemargin, install_getprogsize(argv[i]) );
      -            if (startpage < 0) {
      -                fprintf(stderr, "Not enough memory\n");
      -                return -ENOMEM;
      -            }
      -                            
      -            if ( (progsize = install_programflash(startaddr, argv[i])) <= 0) {
      -                fprintf(stderr, "Error writing program memory: %s\n"
      +              }
      +
      +            printf("Replacing %s\n", scriptname);
      +          }
      +
      +        startaddr = install_getstartpage(startpage, pagemargin, install_getprogsize(argv[i]));
      +        if (startpage < 0)
      +          {
      +            fprintf(stderr, "Not enough memory\n");
      +            return -ENOMEM;
      +          }
      +
      +        if ((progsize = install_programflash(startaddr, argv[i])) <= 0)
      +          {
      +            fprintf(stderr, "Error writing program memory: %s\n"
                           "Note: Flash pages are not released, so you may try again and program will be\n"
      -                    "      written in other pages.\n", strerror(-progsize) );
      -                
      -                return -EIO;
      -            }
      -            if ( (scrsta = install_createscript(startaddr, stacksize, progsize, 
      -                                           priority, scriptname)) < 0) {
      -                fprintf(stderr, "Error writing program script at %s: %s\n", 
      -                    argv[i+1], strerror(-scrsta) );
      -                return -EIO;
      -            }
      -            
      -            printf("Installed application of size %d bytes to program memory [%xh - %xh].\n",
      +                    "      written in other pages.\n", strerror(-progsize));
      +            return -EIO;
      +          }
      +
      +        if ((scrsta = install_createscript(startaddr, stacksize, progsize,
      +                                             priority, scriptname)) < 0)
      +          {
      +            fprintf(stderr, "Error writing program script at %s: %s\n",
      +                    argv[i+1], strerror(-scrsta));
      +            return -EIO;
      +          }
      +
      +        printf("Installed application of size %d bytes to program memory [%xh - %xh].\n",
                       progsize, startaddr, startaddr + progsize);
      -
      -            return 0;
      +        return 0;
           }
      -    
      -    fprintf(stderr, install_help, argv[0], argv[0]);
      -    return -1;
      +
      +  fprintf(stderr, install_help, argv[0], argv[0]);
      +  return -1;
       }
      diff --git a/apps/system/poweroff/Kconfig b/apps/system/poweroff/Kconfig
      new file mode 100644
      index 000000000..ae8eac450
      --- /dev/null
      +++ b/apps/system/poweroff/Kconfig
      @@ -0,0 +1,16 @@
      +#
      +# For a description of the syntax of this configuration file,
      +# see misc/tools/kconfig-language.txt.
      +#
      +
      +config SYSTEM_POWEROFF
      +	bool "Power-Off command"
      +	default n
      +	---help---
      +		Enable support for the NSH poweroff command.  NOTE: This option
      +		provides the NSH power-off command only.  It requires board-specific
      +		support to actually implement the power-off.
      +
      +if SYSTEM_POWEROFF
      +endif
      +
      diff --git a/apps/system/poweroff/Makefile b/apps/system/poweroff/Makefile
      new file mode 100644
      index 000000000..40465e957
      --- /dev/null
      +++ b/apps/system/poweroff/Makefile
      @@ -0,0 +1,114 @@
      +############################################################################
      +# apps/system/poweroff/Makefile
      +#
      +#   Copyright (C) 2011 Uros Platise. All rights reserved.
      +#   Author: Uros Platise 
      +#           Gregory Nutt 
      +#
      +# 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.
      +#
      +############################################################################
      +
      +# TODO, this makefile should run make under the app dirs, instead of
      +# sourcing the Make.defs!
      +
      +-include $(TOPDIR)/.config
      +-include $(TOPDIR)/Make.defs
      +include $(APPDIR)/Make.defs
      +
      +ifeq ($(WINTOOL),y)
      +INCDIROPT	= -w
      +endif
      +
      +# Hello Application
      +# TODO: appname can be automatically extracted from the directory name
      +
      +APPNAME		= poweroff
      +PRIORITY	= SCHED_PRIORITY_DEFAULT
      +STACKSIZE	= 768
      +
      +ASRCS		=
      +CSRCS		= poweroff.c
      +
      +AOBJS		= $(ASRCS:.S=$(OBJEXT))
      +COBJS		= $(CSRCS:.c=$(OBJEXT))
      +
      +SRCS		= $(ASRCS) $(CSRCS)
      +OBJS		= $(AOBJS) $(COBJS)
      +
      +ifeq ($(WINTOOL),y)
      +  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +else
      +  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +endif
      +
      +ROOTDEPPATH	= --dep-path .
      +
      +# Common build
      +
      +VPATH		= 
      +
      +all:	.built
      +.PHONY: context depend clean distclean
      +
      +$(AOBJS): %$(OBJEXT): %.S
      +	$(call ASSEMBLE, $<, $@)
      +
      +$(COBJS): %$(OBJEXT): %.c
      +	$(call COMPILE, $<, $@)
      +
      +.built: $(OBJS)
      +	@( for obj in $(OBJS) ; do \
      +		$(call ARCHIVE, $(BIN), $${obj}); \
      +	done ; )
      +	@touch .built
      +
      +# Register application
      +
      +.context:
      +	$(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main)
      +	@touch $@
      +
      +context: .context
      +
      +# Create dependencies
      +
      +.depend: Makefile $(SRCS)
      +	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@touch $@
      +
      +depend: .depend
      +
      +clean:
      +	@rm -f *.o *~ .*.swp .built
      +	$(call CLEAN)
      +
      +distclean: clean
      +	@rm -f .context Make.dep .depend
      +
      +-include Make.dep
      diff --git a/apps/system/poweroff/README.txt b/apps/system/poweroff/README.txt
      new file mode 100644
      index 000000000..e02180e5a
      --- /dev/null
      +++ b/apps/system/poweroff/README.txt
      @@ -0,0 +1,5 @@
      +
      +This application provides poweroff command
      +
      +	Source: NuttX
      +	Date: 13. March 2011
      diff --git a/apps/system/poweroff/poweroff.c b/apps/system/poweroff/poweroff.c
      new file mode 100644
      index 000000000..dd08b177a
      --- /dev/null
      +++ b/apps/system/poweroff/poweroff.c
      @@ -0,0 +1,63 @@
      +/****************************************************************************
      + * apps/system/poweroff/poweroff.c
      + *
      + *   Copyright (C) 2011 Uros Platise. All rights reserved.
      + *   Author: Uros Platise 
      + *
      + * Redistribution and use in source and binary forms, with or without
      + * modification, are permitted provided that the following conditions
      + * are met:
      + *
      + * 1. Redistributions of source code must retain the above copyright
      + *    notice, this list of conditions and the following disclaimer.
      + * 2. Redistributions in binary form must reproduce the above copyright
      + *    notice, this list of conditions and the following disclaimer in
      + *    the documentation and/or other materials provided with the
      + *    distribution.
      + * 3. Neither the name NuttX nor the names of its contributors may be
      + *    used to endorse or promote products derived from this software
      + *    without specific prior written permission.
      + *
      + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
      + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
      + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
      + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
      + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
      + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
      + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
      + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
      + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
      + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
      + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
      + * POSSIBILITY OF SUCH DAMAGE.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +int poweroff_main(int argc, char *argv[])
      +{
      +  /* TODO:
      +   *  - replace this by sending general system signal to shutdown, where i.e. nsh
      +   *    must issue down script (it may check whether nsh is running before spawning
      +   *    a new process with nsh poweroff)
      +   *  - wait for some time (~0.5 second for VSN), that SDcard is flashed and synced
      +   *  - call poweroff
      +   * 
      +   * TODO on boot:
      +   *  - if external key is pressed, do not start the nsh! but wait until it is released
      +   *    (to get rid of bad mounts of the sdcard etc.) this could be handled in the 
      +   *    button driver immediately on system boot
      +   */
      +
      +  board_power_off();
      +  return 0;
      +}
      diff --git a/apps/system/ramtron/Kconfig b/apps/system/ramtron/Kconfig
      new file mode 100644
      index 000000000..53d547e5f
      --- /dev/null
      +++ b/apps/system/ramtron/Kconfig
      @@ -0,0 +1,14 @@
      +#
      +# For a description of the syntax of this configuration file,
      +# see misc/tools/kconfig-language.txt.
      +#
      +
      +config SYSTEM_RAMTRON
      +	bool "RAMTRON command"
      +	default n
      +	---help---
      +		Enable support for the NSH RAMTRON command.
      +
      +if SYSTEM_RAMTRON
      +endif
      +
      diff --git a/apps/system/ramtron/Makefile b/apps/system/ramtron/Makefile
      new file mode 100644
      index 000000000..030ef6d5c
      --- /dev/null
      +++ b/apps/system/ramtron/Makefile
      @@ -0,0 +1,114 @@
      +############################################################################
      +# apps/system/ramtron/Makefile
      +#
      +#   Copyright (C) 2011 Uros Platise. All rights reserved.
      +#   Author: Uros Platise 
      +#           Gregory Nutt 
      +#
      +# 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.
      +#
      +############################################################################
      +
      +# TODO, this makefile should run make under the app dirs, instead of
      +# sourcing the Make.defs!
      +
      +-include $(TOPDIR)/.config
      +-include $(TOPDIR)/Make.defs
      +include $(APPDIR)/Make.defs
      +
      +ifeq ($(WINTOOL),y)
      +INCDIROPT	= -w
      +endif
      +
      +# Hello Application
      +# TODO: appname can be automatically extracted from the directory name
      +
      +APPNAME		= ramtron
      +PRIORITY	= SCHED_PRIORITY_DEFAULT
      +STACKSIZE	= 1024
      +
      +ASRCS		=
      +CSRCS		= ramtron.c
      +
      +AOBJS		= $(ASRCS:.S=$(OBJEXT))
      +COBJS		= $(CSRCS:.c=$(OBJEXT))
      +
      +SRCS		= $(ASRCS) $(CSRCS)
      +OBJS		= $(AOBJS) $(COBJS)
      +
      +ifeq ($(WINTOOL),y)
      +  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +else
      +  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +endif
      +
      +ROOTDEPPATH	= --dep-path .
      +
      +# Common build
      +
      +VPATH		= 
      +
      +all:	.built
      +.PHONY: context depend clean distclean
      +
      +$(AOBJS): %$(OBJEXT): %.S
      +	$(call ASSEMBLE, $<, $@)
      +
      +$(COBJS): %$(OBJEXT): %.c
      +	$(call COMPILE, $<, $@)
      +
      +.built: $(OBJS)
      +	@( for obj in $(OBJS) ; do \
      +		$(call ARCHIVE, $(BIN), $${obj}); \
      +	done ; )
      +	@touch .built
      +
      +# Register application
      +
      +.context:
      +	$(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main)
      +	@touch $@
      +
      +context: .context
      +
      +# Create dependencies
      +
      +.depend: Makefile $(SRCS)
      +	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@touch $@
      +
      +depend: .depend
      +
      +clean:
      +	@rm -f *.o *~ .*.swp .built
      +	$(call CLEAN)
      +
      +distclean: clean
      +	@rm -f .context Make.dep .depend
      +
      +-include Make.dep
      diff --git a/apps/system/ramtron/README.txt b/apps/system/ramtron/README.txt
      new file mode 100644
      index 000000000..152774b66
      --- /dev/null
      +++ b/apps/system/ramtron/README.txt
      @@ -0,0 +1,7 @@
      +
      +This application provides RAMTRON tool/lib to start, stop or to perform
      +RAMTRON custom operations.
      +
      +	Source: NuttX
      +	Author: Uros Platise
      +	Date: 18. March 2011
      diff --git a/apps/system/ramtron/ramtron.c b/apps/system/ramtron/ramtron.c
      new file mode 100644
      index 000000000..cd4012787
      --- /dev/null
      +++ b/apps/system/ramtron/ramtron.c
      @@ -0,0 +1,104 @@
      +/****************************************************************************
      + * ramtron/ramtron.c
      + *
      + *   Copyright (C) 2011 Uros Platise. All rights reserved.
      + *   Copyright (C) 2009 Gregory Nutt. All rights reserved.
      + *
      + *   Authors: Uros Platise 
      + *            Gregory Nutt 
      + *
      + * 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.
      + *
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +#include 
      +#include 
      +
      +FAR struct mtd_dev_s *ramtron_initialize(FAR struct spi_dev_s *dev);
      +
      +int ramtron_start(int spino)
      +{
      +  FAR struct spi_dev_s *spi;
      +  FAR struct mtd_dev_s *mtd;
      +  int retval;
      +
      +  /* Get the SPI port */
      +  
      +  spi = up_spiinitialize(spino);
      +  if (!spi)
      +    {
      +      printf("RAMTRON: Failed to initialize SPI%d\n", spino);
      +      return -ENODEV;
      +    }
      +
      +  printf("RAMTRON: Initialized SPI%d\n", spino);
      +
      +  mtd = (struct mtd_dev_s *)ramtron_initialize(spi);
      +  if (!mtd)
      +    {
      +      printf("RAMTRON: Device not found\n");
      +      return -ENODEV;
      +    }
      +
      +    printf("RAMTRON: FM25V10 of size 128 kB\n");
      +  //printf("RAMTRON: %s of size %d B\n", ramtron_getpart(mtd), ramtron_getsize(mtd) );
      +
      +  retval = ftl_initialize(0, mtd);
      +  printf("RAMTRON: FTL Initialized (returns with %d)\n", retval);
      +
      +  return OK;
      +}
      +
      +
      +int ramtron_main(int argc, char *argv[])
      +{
      +  int spino;
      +  
      +  if (argc == 3)
      +    {
      +      spino = atoi(argv[2]);
      +    
      +      if (!strcmp(argv[1], "start"))
      +        {
      +        return ramtron_start(spino);
      +        }
      +    }
      +  
      +  /* todo: write protect */
      +
      +  printf("%s:  \n", argv[0]);
      +  return -1;
      +}
      diff --git a/apps/system/sdcard/Kconfig b/apps/system/sdcard/Kconfig
      new file mode 100644
      index 000000000..a1a8a1f32
      --- /dev/null
      +++ b/apps/system/sdcard/Kconfig
      @@ -0,0 +1,14 @@
      +#
      +# For a description of the syntax of this configuration file,
      +# see misc/tools/kconfig-language.txt.
      +#
      +
      +config SYSTEM_SDCARD
      +	bool "NSH sdcard command"
      +	default n
      +	---help---
      +		Enable support for the NSH sdcard command.
      +
      +if SYSTEM_SDCARD
      +endif
      +
      diff --git a/apps/system/sdcard/Makefile b/apps/system/sdcard/Makefile
      new file mode 100644
      index 000000000..fef049a59
      --- /dev/null
      +++ b/apps/system/sdcard/Makefile
      @@ -0,0 +1,114 @@
      +############################################################################
      +# apps/system/sdcard/Makefile
      +#
      +#   Copyright (C) 2011 Uros Platise. All rights reserved.
      +#   Author: Uros Platise 
      +#           Gregory Nutt 
      +#
      +# 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.
      +#
      +############################################################################
      +
      +# TODO, this makefile should run make under the app dirs, instead of
      +# sourcing the Make.defs!
      +
      +-include $(TOPDIR)/.config
      +-include $(TOPDIR)/Make.defs
      +include $(APPDIR)/Make.defs
      +
      +ifeq ($(WINTOOL),y)
      +INCDIROPT	= -w
      +endif
      +
      +# Hello Application
      +# TODO: appname can be automatically extracted from the directory name
      +
      +APPNAME		= sdcard
      +PRIORITY	= SCHED_PRIORITY_DEFAULT
      +STACKSIZE	= 1024
      +
      +ASRCS		=
      +CSRCS		= sdcard.c
      +
      +AOBJS		= $(ASRCS:.S=$(OBJEXT))
      +COBJS		= $(CSRCS:.c=$(OBJEXT))
      +
      +SRCS		= $(ASRCS) $(CSRCS)
      +OBJS		= $(AOBJS) $(COBJS)
      +
      +ifeq ($(WINTOOL),y)
      +  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +else
      +  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +endif
      +
      +ROOTDEPPATH	= --dep-path .
      +
      +# Common build
      +
      +VPATH		= 
      +
      +all:	.built
      +.PHONY: context depend clean distclean
      +
      +$(AOBJS): %$(OBJEXT): %.S
      +	$(call ASSEMBLE, $<, $@)
      +
      +$(COBJS): %$(OBJEXT): %.c
      +	$(call COMPILE, $<, $@)
      +
      +.built: $(OBJS)
      +	@( for obj in $(OBJS) ; do \
      +		$(call ARCHIVE, $(BIN), $${obj}); \
      +	done ; )
      +	@touch .built
      +
      +# Register application
      +
      +.context:
      +	$(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main)
      +	@touch $@
      +
      +context: .context
      +
      +# Create dependencies
      +
      +.depend: Makefile $(SRCS)
      +	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@touch $@
      +
      +depend: .depend
      +
      +clean:
      +	@rm -f *.o *~ .*.swp .built
      +	$(call CLEAN)
      +
      +distclean: clean
      +	@rm -f .context Make.dep .depend
      +
      +-include Make.dep
      diff --git a/apps/system/sdcard/README.txt b/apps/system/sdcard/README.txt
      new file mode 100644
      index 000000000..332aa26cf
      --- /dev/null
      +++ b/apps/system/sdcard/README.txt
      @@ -0,0 +1,7 @@
      +
      +This application provides SDcard tool/lib to start, stop, eject or insert
      +a memory card.
      +
      +	Source: NuttX
      +	Author: Uros Platise
      +	Date: 18. March 2011
      diff --git a/apps/system/sdcard/sdcard.c b/apps/system/sdcard/sdcard.c
      new file mode 100644
      index 000000000..56ab74f44
      --- /dev/null
      +++ b/apps/system/sdcard/sdcard.c
      @@ -0,0 +1,161 @@
      +/****************************************************************************
      + * apps/system/sdcard/sdcard.c
      + *
      + *   Copyright (C) 2011 Uros Platise. All rights reserved.
      + *   Copyright (C) 2009 Gregory Nutt. All rights reserved.
      + *
      + *   Authors: Uros Platise 
      + *            Gregory Nutt 
      + *
      + * Redistribution and use in source and binary forms, with or without
      + * modification, are permitted provided that the following conditions
      + * are met:
      + *
      + * 1. Redistributions of source code must retain the above copyright
      + *    notice, this list of conditions and the following disclaimer.
      + * 2. Redistributions in binary form must reproduce the above copyright
      + *    notice, this list of conditions and the following disclaimer in
      + *    the documentation and/or other materials provided with the
      + *    distribution.
      + * 3. Neither the name NuttX nor the names of its contributors may be
      + *    used to endorse or promote products derived from this software
      + *    without specific prior written permission.
      + *
      + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
      + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
      + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
      + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
      + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
      + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
      + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
      + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
      + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
      + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
      + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
      + * POSSIBILITY OF SUCH DAMAGE.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +#ifdef CONFIG_STM32_SDIO
      +#  include 
      +#  include 
      +#endif
      +
      +/****************************************************************************
      + * Public Function Prototypes
      + ****************************************************************************/
      +
      +FAR struct sdio_dev_s *sdio_initialize(int slotno);
      +void sdio_mediachange(FAR struct sdio_dev_s *dev, bool cardinslot);
      +
      +// TODO get the structure out from the slot number
      +static FAR struct sdio_dev_s *sdio = NULL;
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/* Create device device for the SDIO-based MMC/SD block driver */
      +
      +static int sdcard_start(int slotno)
      +{
      +  int ret;
      +
      +  /* First, get an instance of the SDIO interface */
      +
      +  sdio = sdio_initialize(slotno);
      +  if (!sdio)
      +    {
      +      printf("SDIO: Failed to initialize slot %d\n", slotno);
      +      return -ENODEV;
      +    }
      +
      +  printf("SDIO: Initialized slot %d\n", slotno);
      +
      +  /* Now bind the SPI interface to the MMC/SD driver */
      +
      +  ret = mmcsd_slotinitialize(slotno, sdio);
      +  if (ret != OK)
      +    {
      +      printf("SDIO: Failed to bind to the MMC/SD driver: %d\n", ret);
      +      return ret;
      +    }
      +
      +  printf("SDIO: Successfully bound to the MMC/SD driver\n");
      +
      +  /* Then let's guess and say that there is a card in the slot.  I need to check to
      +   * see if the VSN board supports a GPIO to detect if there is a card in
      +   * the slot.
      +   */
      +  sdio_mediachange(sdio, true);
      +
      +  return OK;
      +}
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +int sdcard_main(int argc, char *argv[])
      +{
      +  int slotno = 0;
      +
      +  if (argc >= 2) {
      +
      +      /* The 3rd argument is expected to be a slot number, if given */
      +
      +      if (argc==3)
      +        {
      +          slotno = atoi(argv[2]);
      +        }
      +
      +      /* Commands */
      +
      +      if (!strcmp(argv[1], "start"))
      +        {
      +          return sdcard_start(slotno);
      +        }
      +      else if (!strcmp(argv[1], "stop"))
      +        {
      +          fprintf(stderr, "Not implemented yet\n");
      +        }
      +      else if (!strcmp(argv[1], "insert"))
      +        {
      +          if (sdio)
      +            {
      +              sdio_mediachange(sdio, true);
      +              return OK;
      +            }
      +        }
      +      else if (!strcmp(argv[1], "eject"))
      +        {
      +          if (sdio)
      +            {
      +              sdio_mediachange(sdio, false);
      +              return OK;
      +            }
      +        }
      +      else if (!strcmp(argv[1], "status"))
      +        {
      +          printf("SDcard #%d Status:\n", slotno);
      +#ifndef CONFIG_MMCSD_HAVECARDDETECT
      +          printf("\t - Without SDcard detect capability\n");
      +#endif
      +          return 0;
      +        }
      +    }
      +
      +  printf("%s:  {slotno}\n", argv[0]);
      +  return -1;
      +}
      diff --git a/apps/system/sysinfo/Kconfig b/apps/system/sysinfo/Kconfig
      new file mode 100644
      index 000000000..1f106dc8a
      --- /dev/null
      +++ b/apps/system/sysinfo/Kconfig
      @@ -0,0 +1,13 @@
      +#
      +# For a description of the syntax of this configuration file,
      +# see misc/tools/kconfig-language.txt.
      +#
      +
      +config SYSTEM_SYSINFO
      +	bool "NSH sysinfo command"
      +	default n
      +	---help---
      +		Enable support for the NSH sysinfo command.
      +
      +if SYSTEM_SYSINFO
      +endif
      diff --git a/apps/system/sysinfo/Makefile b/apps/system/sysinfo/Makefile
      new file mode 100644
      index 000000000..ead974277
      --- /dev/null
      +++ b/apps/system/sysinfo/Makefile
      @@ -0,0 +1,114 @@
      +############################################################################
      +# apps/system/sysinfo/Makefile
      +#
      +#   Copyright (C) 2011 Uros Platise. All rights reserved.
      +#   Author: Uros Platise 
      +#           Gregory Nutt 
      +#
      +# 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.
      +#
      +############################################################################
      +
      +# TODO, this makefile should run make under the app dirs, instead of
      +# sourcing the Make.defs!
      +
      +-include $(TOPDIR)/.config
      +-include $(TOPDIR)/Make.defs
      +include $(APPDIR)/Make.defs
      +
      +ifeq ($(WINTOOL),y)
      +INCDIROPT	= -w
      +endif
      +
      +# Hello Application
      +# TODO: appname can be automatically extracted from the directory name
      +
      +APPNAME		= sysinfo
      +PRIORITY	= SCHED_PRIORITY_DEFAULT
      +STACKSIZE	= 768
      +
      +ASRCS		=
      +CSRCS		= sysinfo.c
      +
      +AOBJS		= $(ASRCS:.S=$(OBJEXT))
      +COBJS		= $(CSRCS:.c=$(OBJEXT))
      +
      +SRCS		= $(ASRCS) $(CSRCS)
      +OBJS		= $(AOBJS) $(COBJS)
      +
      +ifeq ($(WINTOOL),y)
      +  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +else
      +  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +endif
      +
      +ROOTDEPPATH	= --dep-path .
      +
      +# Common build
      +
      +VPATH		= 
      +
      +all:	.built
      +.PHONY: context depend clean distclean
      +
      +$(AOBJS): %$(OBJEXT): %.S
      +	$(call ASSEMBLE, $<, $@)
      +
      +$(COBJS): %$(OBJEXT): %.c
      +	$(call COMPILE, $<, $@)
      +
      +.built: $(OBJS)
      +	@( for obj in $(OBJS) ; do \
      +		$(call ARCHIVE, $(BIN), $${obj}); \
      +	done ; )
      +	@touch .built
      +
      +# Register application
      +
      +.context:
      +	$(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main)
      +	@touch $@
      +
      +context: .context
      +
      +# Create dependencies
      +
      +.depend: Makefile $(SRCS)
      +	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@touch $@
      +
      +depend: .depend
      +
      +clean:
      +	@rm -f *.o *~ .*.swp .built
      +	$(call CLEAN)
      +
      +distclean: clean
      +	@rm -f .context Make.dep .depend
      +
      +-include Make.dep
      diff --git a/apps/system/sysinfo/README.txt b/apps/system/sysinfo/README.txt
      new file mode 100644
      index 000000000..3792f4a59
      --- /dev/null
      +++ b/apps/system/sysinfo/README.txt
      @@ -0,0 +1,6 @@
      +
      +This application provides access to System Information
      +
      +	Source: NuttX
      +	Date: 15. April 2011
      +    Author: Uros Platise 
      diff --git a/apps/system/sysinfo/sysinfo.c b/apps/system/sysinfo/sysinfo.c
      new file mode 100644
      index 000000000..019e910db
      --- /dev/null
      +++ b/apps/system/sysinfo/sysinfo.c
      @@ -0,0 +1,69 @@
      +/****************************************************************************
      + * apps/system/sysinfo/sysinfo.c
      + *
      + *   Copyright (C) 2011 Uros Platise. All rights reserved.
      + *   Author: Uros Platise 
      + *
      + * 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.
      + *
      + ****************************************************************************/
      +
      +/* Collects and reports system information.
      + *
      + * TODO: Gather information also from low-level devices, kernel/sched, clock,
      + *   and further reporting as: sysinfo rtc, or sysinfo sched, ... with
      + *   sysinfo help to report all of the options.
      + */
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include 
      +#include 
      +
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +int sysinfo_main(int argc, char *argv[])
      +{
      +  printf("System Information:\n");
      +  printf("\tNuttX Version:\t" CONFIG_VERSION_STRING
      +         " Build: %d\n", CONFIG_VERSION_BUILD);
      +  printf("\tSystem Time:\t%d [s] UTC "
      +#ifdef CONFIG_RTC
      +        "Hardware RTC Support"
      +#endif
      +        "\n", time(NULL) );
      +  return 0;
      +}
      diff --git a/apps/vsn/Kconfig b/apps/vsn/Kconfig
      deleted file mode 100644
      index 1f0c25f16..000000000
      --- a/apps/vsn/Kconfig
      +++ /dev/null
      @@ -1,11 +0,0 @@
      -#
      -# For a description of the syntax of this configuration file,
      -# see misc/tools/kconfig-language.txt.
      -#
      -
      -comment "VSN board add-ons"
      -
      -source "$APPSDIR/vsn/poweroff/Kconfig"
      -source "$APPSDIR/vsn/ramtron/Kconfig"
      -source "$APPSDIR/vsn/sdcard/Kconfig"
      -source "$APPSDIR/vsn/sysinfo/Kconfig"
      diff --git a/apps/vsn/Make.defs b/apps/vsn/Make.defs
      deleted file mode 100644
      index 6d59ab838..000000000
      --- a/apps/vsn/Make.defs
      +++ /dev/null
      @@ -1,51 +0,0 @@
      -############################################################################
      -# apps/vsn/Make.defs
      -# Adds selected applications to apps/ build
      -#
      -#   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      -#   Author: Gregory Nutt 
      -#
      -# 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.
      -#
      -############################################################################
      -
      -ifeq ($(CONFIG_VSN_POWEROFF),y)
      -CONFIGURED_APPS += vsn/poweroff
      -endif
      -
      -ifeq ($(CONFIG_VSN_RAMTRON),y)
      -CONFIGURED_APPS += vsn/ramtron
      -endif
      -
      -ifeq ($(CONFIG_VSN_SDCARD),y)
      -CONFIGURED_APPS += vsn/sdcard
      -endif
      -
      -ifeq ($(CONFIG_VSN_SYSINFO),y)
      -CONFIGURED_APPS += vsn/sysinfo
      -endif
      diff --git a/apps/vsn/Makefile b/apps/vsn/Makefile
      deleted file mode 100644
      index 21901d96d..000000000
      --- a/apps/vsn/Makefile
      +++ /dev/null
      @@ -1,71 +0,0 @@
      -############################################################################
      -# apps/vsn/Makefile
      -#
      -#   Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
      -#   Author: Gregory Nutt 
      -#
      -# 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.
      -#
      -############################################################################
      -
      --include $(TOPDIR)/.config	# Current configuration
      -
      -# Sub-directories
      -
      -SUBDIRS = poweroff ramtron sdcard sysinfo
      -
      -all: nothing
      -.PHONY: nothing context depend clean distclean
      -
      -nothing:
      -
      -.context:
      -	@for dir in $(SUBDIRS) ; do \
      -		$(MAKE) -C $$dir context TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \
      -	done
      -	@touch $@
      -
      -context: .context
      -
      -depend:
      -	@for dir in $(SUBDIRS) ; do \
      -		$(MAKE) -C $$dir depend TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \
      -	done
      -
      -clean:
      -	@for dir in $(SUBDIRS) ; do \
      -		$(MAKE) -C $$dir clean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \
      -	done
      -
      -distclean: clean
      -	@for dir in $(SUBDIRS) ; do \
      -		$(MAKE) -C $$dir distclean TOPDIR="$(TOPDIR)" APPDIR=$(APPDIR); \
      -	done
      -
      --include Make.dep
      -
      diff --git a/apps/vsn/poweroff/Kconfig b/apps/vsn/poweroff/Kconfig
      deleted file mode 100644
      index d0059a0d3..000000000
      --- a/apps/vsn/poweroff/Kconfig
      +++ /dev/null
      @@ -1,14 +0,0 @@
      -#
      -# For a description of the syntax of this configuration file,
      -# see misc/tools/kconfig-language.txt.
      -#
      -
      -config VSN_POWEROFF
      -	bool "NSH poweroff command"
      -	default n
      -	---help---
      -		Enable support for the NSH poweroff command.
      -
      -if VSN_POWEROFF
      -endif
      -
      diff --git a/apps/vsn/poweroff/Makefile b/apps/vsn/poweroff/Makefile
      deleted file mode 100644
      index e58ecfa86..000000000
      --- a/apps/vsn/poweroff/Makefile
      +++ /dev/null
      @@ -1,114 +0,0 @@
      -############################################################################
      -# Makefile
      -#
      -#   Copyright (C) 2011 Uros Platise. All rights reserved.
      -#   Author: Uros Platise 
      -#           Gregory Nutt 
      -#
      -# 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.
      -#
      -############################################################################
      -
      -# TODO, this makefile should run make under the app dirs, instead of
      -# sourcing the Make.defs!
      -
      --include $(TOPDIR)/.config
      --include $(TOPDIR)/Make.defs
      -include $(APPDIR)/Make.defs
      -
      -ifeq ($(WINTOOL),y)
      -INCDIROPT	= -w
      -endif
      -
      -# Hello Application
      -# TODO: appname can be automatically extracted from the directory name
      -
      -APPNAME		= poweroff
      -PRIORITY	= SCHED_PRIORITY_DEFAULT
      -STACKSIZE	= 768
      -
      -ASRCS		=
      -CSRCS		= poweroff.c
      -
      -AOBJS		= $(ASRCS:.S=$(OBJEXT))
      -COBJS		= $(CSRCS:.c=$(OBJEXT))
      -
      -SRCS		= $(ASRCS) $(CSRCS)
      -OBJS		= $(AOBJS) $(COBJS)
      -
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      -else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      -endif
      -
      -ROOTDEPPATH	= --dep-path .
      -
      -# Common build
      -
      -VPATH		= 
      -
      -all:	.built
      -.PHONY: context depend clean distclean
      -
      -$(AOBJS): %$(OBJEXT): %.S
      -	$(call ASSEMBLE, $<, $@)
      -
      -$(COBJS): %$(OBJEXT): %.c
      -	$(call COMPILE, $<, $@)
      -
      -.built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      -	@touch .built
      -
      -# Register application
      -
      -.context:
      -	$(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main)
      -	@touch $@
      -
      -context: .context
      -
      -# Create dependencies
      -
      -.depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      -	@touch $@
      -
      -depend: .depend
      -
      -clean:
      -	@rm -f *.o *~ .*.swp .built
      -	$(call CLEAN)
      -
      -distclean: clean
      -	@rm -f .context Make.dep .depend
      -
      --include Make.dep
      diff --git a/apps/vsn/poweroff/README.txt b/apps/vsn/poweroff/README.txt
      deleted file mode 100644
      index e02180e5a..000000000
      --- a/apps/vsn/poweroff/README.txt
      +++ /dev/null
      @@ -1,5 +0,0 @@
      -
      -This application provides poweroff command
      -
      -	Source: NuttX
      -	Date: 13. March 2011
      diff --git a/apps/vsn/poweroff/poweroff.c b/apps/vsn/poweroff/poweroff.c
      deleted file mode 100644
      index ca3f056e8..000000000
      --- a/apps/vsn/poweroff/poweroff.c
      +++ /dev/null
      @@ -1,54 +0,0 @@
      -/****************************************************************************
      - * poweroff/poweroff.c
      - *
      - *   Copyright (C) 2011 Uros Platise. All rights reserved.
      - *   Author: Uros Platise 
      - *
      - * 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.
      - *
      - ****************************************************************************/
      -
      -#include 
      -
      -int poweroff_main(int argc, char *argv[])
      -{
      -/* TODO:
      - *  - replace this by sending general system signal to shutdown, where i.e. nsh
      - *    must issue down script (it may check whether nsh is running before spawning
      - *    a new process with nsh poweroff)
      - *  - wait for some time (~0.5 second for VSN), that SDcard is flashed and synced
      - *  - call poweroff
      - * 
      - * TODO on boot:
      - *  - if external key is pressed, do not start the nsh! but wait until it is released
      - *    (to get rid of bad mounts of the sdcard etc.) this could be handled in the 
      - *    button driver immediately on system boot
      - */
      -	board_power_off();
      -	return 0;
      -}
      diff --git a/apps/vsn/ramtron/Kconfig b/apps/vsn/ramtron/Kconfig
      deleted file mode 100644
      index 14f358921..000000000
      --- a/apps/vsn/ramtron/Kconfig
      +++ /dev/null
      @@ -1,14 +0,0 @@
      -#
      -# For a description of the syntax of this configuration file,
      -# see misc/tools/kconfig-language.txt.
      -#
      -
      -config VSN_RAMTRON
      -	bool "NSH ramtron command"
      -	default n
      -	---help---
      -		Enable support for the NSH ramtron command.
      -
      -if VSN_RAMTRON
      -endif
      -
      diff --git a/apps/vsn/ramtron/Makefile b/apps/vsn/ramtron/Makefile
      deleted file mode 100644
      index d930aa92c..000000000
      --- a/apps/vsn/ramtron/Makefile
      +++ /dev/null
      @@ -1,114 +0,0 @@
      -############################################################################
      -# Makefile
      -#
      -#   Copyright (C) 2011 Uros Platise. All rights reserved.
      -#   Author: Uros Platise 
      -#           Gregory Nutt 
      -#
      -# 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.
      -#
      -############################################################################
      -
      -# TODO, this makefile should run make under the app dirs, instead of
      -# sourcing the Make.defs!
      -
      --include $(TOPDIR)/.config
      --include $(TOPDIR)/Make.defs
      -include $(APPDIR)/Make.defs
      -
      -ifeq ($(WINTOOL),y)
      -INCDIROPT	= -w
      -endif
      -
      -# Hello Application
      -# TODO: appname can be automatically extracted from the directory name
      -
      -APPNAME		= ramtron
      -PRIORITY	= SCHED_PRIORITY_DEFAULT
      -STACKSIZE	= 1024
      -
      -ASRCS		=
      -CSRCS		= ramtron.c
      -
      -AOBJS		= $(ASRCS:.S=$(OBJEXT))
      -COBJS		= $(CSRCS:.c=$(OBJEXT))
      -
      -SRCS		= $(ASRCS) $(CSRCS)
      -OBJS		= $(AOBJS) $(COBJS)
      -
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      -else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      -endif
      -
      -ROOTDEPPATH	= --dep-path .
      -
      -# Common build
      -
      -VPATH		= 
      -
      -all:	.built
      -.PHONY: context depend clean distclean
      -
      -$(AOBJS): %$(OBJEXT): %.S
      -	$(call ASSEMBLE, $<, $@)
      -
      -$(COBJS): %$(OBJEXT): %.c
      -	$(call COMPILE, $<, $@)
      -
      -.built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      -	@touch .built
      -
      -# Register application
      -
      -.context:
      -	$(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main)
      -	@touch $@
      -
      -context: .context
      -
      -# Create dependencies
      -
      -.depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      -	@touch $@
      -
      -depend: .depend
      -
      -clean:
      -	@rm -f *.o *~ .*.swp .built
      -	$(call CLEAN)
      -
      -distclean: clean
      -	@rm -f .context Make.dep .depend
      -
      --include Make.dep
      diff --git a/apps/vsn/ramtron/README.txt b/apps/vsn/ramtron/README.txt
      deleted file mode 100644
      index 152774b66..000000000
      --- a/apps/vsn/ramtron/README.txt
      +++ /dev/null
      @@ -1,7 +0,0 @@
      -
      -This application provides RAMTRON tool/lib to start, stop or to perform
      -RAMTRON custom operations.
      -
      -	Source: NuttX
      -	Author: Uros Platise
      -	Date: 18. March 2011
      diff --git a/apps/vsn/ramtron/ramtron.c b/apps/vsn/ramtron/ramtron.c
      deleted file mode 100644
      index f1e8db100..000000000
      --- a/apps/vsn/ramtron/ramtron.c
      +++ /dev/null
      @@ -1,99 +0,0 @@
      -/****************************************************************************
      - * ramtron/ramtron.c
      - *
      - *   Copyright (C) 2011 Uros Platise. All rights reserved.
      - *   Copyright (C) 2009 Gregory Nutt. All rights reserved.
      - *
      - *   Authors: Uros Platise 
      - *            Gregory Nutt 
      - *
      - * 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.
      - *
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -#include 
      -#include 
      -
      -FAR struct mtd_dev_s *ramtron_initialize(FAR struct spi_dev_s *dev);
      -
      -int ramtron_start(int spino)
      -{
      -  FAR struct spi_dev_s *spi;
      -  FAR struct mtd_dev_s *mtd;
      -  int retval;
      -
      -  /* Get the SPI port */
      -  
      -  spi = up_spiinitialize(spino);
      -  if (!spi)
      -    {
      -      printf("RAMTRON: Failed to initialize SPI%d\n", spino);
      -      return -ENODEV;
      -    }
      -  printf("RAMTRON: Initialized SPI%d\n", spino);
      -
      -  mtd = (struct mtd_dev_s *)ramtron_initialize(spi);
      -  if (!mtd)
      -    {
      -      printf("RAMTRON: Device not found\n");
      -      return -ENODEV;
      -    }
      -  printf("RAMTRON: FM25V10 of size 128 kB\n");
      -  //printf("RAMTRON: %s of size %d B\n", ramtron_getpart(mtd), ramtron_getsize(mtd) );
      -
      -  retval = ftl_initialize(0, mtd);
      -  printf("RAMTRON: FTL Initialized (returns with %d)\n", retval);
      -
      -  return OK;
      -}
      -
      -
      -int ramtron_main(int argc, char *argv[])
      -{
      -  int spino;
      -  
      -  if (argc == 3) {
      -    spino = atoi(argv[2]);
      -    
      -    if (!strcmp(argv[1], "start")) {
      -      return ramtron_start(spino);
      -    }
      -  }
      -  
      -  // todo: write protect  
      -  printf("%s:  \n", argv[0]);
      -  return -1;
      -}
      diff --git a/apps/vsn/sdcard/Kconfig b/apps/vsn/sdcard/Kconfig
      deleted file mode 100644
      index 8e6c13264..000000000
      --- a/apps/vsn/sdcard/Kconfig
      +++ /dev/null
      @@ -1,14 +0,0 @@
      -#
      -# For a description of the syntax of this configuration file,
      -# see misc/tools/kconfig-language.txt.
      -#
      -
      -config VSN_SDCARD
      -	bool "NSH sdcard command"
      -	default n
      -	---help---
      -		Enable support for the NSH sdcard command.
      -
      -if VSN_SDCARD
      -endif
      -
      diff --git a/apps/vsn/sdcard/Makefile b/apps/vsn/sdcard/Makefile
      deleted file mode 100644
      index 213021b25..000000000
      --- a/apps/vsn/sdcard/Makefile
      +++ /dev/null
      @@ -1,114 +0,0 @@
      -############################################################################
      -# Makefile
      -#
      -#   Copyright (C) 2011 Uros Platise. All rights reserved.
      -#   Author: Uros Platise 
      -#           Gregory Nutt 
      -#
      -# 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.
      -#
      -############################################################################
      -
      -# TODO, this makefile should run make under the app dirs, instead of
      -# sourcing the Make.defs!
      -
      --include $(TOPDIR)/.config
      --include $(TOPDIR)/Make.defs
      -include $(APPDIR)/Make.defs
      -
      -ifeq ($(WINTOOL),y)
      -INCDIROPT	= -w
      -endif
      -
      -# Hello Application
      -# TODO: appname can be automatically extracted from the directory name
      -
      -APPNAME		= sdcard
      -PRIORITY	= SCHED_PRIORITY_DEFAULT
      -STACKSIZE	= 1024
      -
      -ASRCS		=
      -CSRCS		= sdcard.c
      -
      -AOBJS		= $(ASRCS:.S=$(OBJEXT))
      -COBJS		= $(CSRCS:.c=$(OBJEXT))
      -
      -SRCS		= $(ASRCS) $(CSRCS)
      -OBJS		= $(AOBJS) $(COBJS)
      -
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      -else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      -endif
      -
      -ROOTDEPPATH	= --dep-path .
      -
      -# Common build
      -
      -VPATH		= 
      -
      -all:	.built
      -.PHONY: context depend clean distclean
      -
      -$(AOBJS): %$(OBJEXT): %.S
      -	$(call ASSEMBLE, $<, $@)
      -
      -$(COBJS): %$(OBJEXT): %.c
      -	$(call COMPILE, $<, $@)
      -
      -.built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      -	@touch .built
      -
      -# Register application
      -
      -.context:
      -	$(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main)
      -	@touch $@
      -
      -context: .context
      -
      -# Create dependencies
      -
      -.depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      -	@touch $@
      -
      -depend: .depend
      -
      -clean:
      -	@rm -f *.o *~ .*.swp .built
      -	$(call CLEAN)
      -
      -distclean: clean
      -	@rm -f .context Make.dep .depend
      -
      --include Make.dep
      diff --git a/apps/vsn/sdcard/README.txt b/apps/vsn/sdcard/README.txt
      deleted file mode 100644
      index 332aa26cf..000000000
      --- a/apps/vsn/sdcard/README.txt
      +++ /dev/null
      @@ -1,7 +0,0 @@
      -
      -This application provides SDcard tool/lib to start, stop, eject or insert
      -a memory card.
      -
      -	Source: NuttX
      -	Author: Uros Platise
      -	Date: 18. March 2011
      diff --git a/apps/vsn/sdcard/sdcard.c b/apps/vsn/sdcard/sdcard.c
      deleted file mode 100644
      index a81e8432a..000000000
      --- a/apps/vsn/sdcard/sdcard.c
      +++ /dev/null
      @@ -1,134 +0,0 @@
      -/****************************************************************************
      - * sdcard/sdcard.c
      - *
      - *   Copyright (C) 2011 Uros Platise. All rights reserved.
      - *   Copyright (C) 2009 Gregory Nutt. All rights reserved.
      - *
      - *   Authors: Uros Platise 
      - *            Gregory Nutt 
      - *
      - * 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.
      - *
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -#ifdef CONFIG_STM32_SDIO
      -#  include 
      -#  include 
      -#endif
      -
      -FAR struct sdio_dev_s *sdio_initialize(int slotno);
      -void sdio_mediachange(FAR struct sdio_dev_s *dev, bool cardinslot);
      -
      -// TODO get the structure out from the slot number
      -static FAR struct sdio_dev_s *sdio = NULL;
      -
      -/* Create device device for the SDIO-based MMC/SD block driver */
      -
      -int sdcard_start(int slotno)
      -{
      -  int ret;
      -
      -  /* First, get an instance of the SDIO interface */
      -
      -  sdio = sdio_initialize(slotno);
      -  if (!sdio)
      -    {
      -      printf("SDIO: Failed to initialize slot %d\n", slotno);
      -      return -ENODEV;
      -    }
      -  printf("SDIO: Initialized slot %d\n", slotno);
      -
      -  /* Now bind the SPI interface to the MMC/SD driver */
      -
      -  ret = mmcsd_slotinitialize(slotno, sdio);
      -  if (ret != OK)
      -    {
      -      printf("SDIO: Failed to bind to the MMC/SD driver: %d\n", ret);
      -      return ret;
      -    }
      -  printf("SDIO: Successfully bound to the MMC/SD driver\n");
      -  
      -  /* Then let's guess and say that there is a card in the slot.  I need to check to
      -   * see if the VSN board supports a GPIO to detect if there is a card in
      -   * the slot.
      -   */
      -  sdio_mediachange(sdio, true);
      -  
      -  return OK;
      -}
      -
      -
      -int sdcard_main(int argc, char *argv[])
      -{
      -    int slotno = 0;
      -  
      -    if (argc >= 2) {
      -    
      -        /* The 3rd argument is expected to be a slot number, if given */
      -        if (argc==3)
      -            slotno = atoi(argv[2]);
      -    
      -        /* Commands */
      -    
      -        if (!strcmp(argv[1], "start")) {
      -            return sdcard_start(slotno);
      -        }
      -        else if (!strcmp(argv[1], "stop")) {
      -            fprintf(stderr, "Not implemented yet\n");
      -        }
      -        else if (!strcmp(argv[1], "insert")) {
      -            if (sdio) {
      -                sdio_mediachange(sdio, true);
      -                return OK;
      -            }
      -        }
      -        else if (!strcmp(argv[1], "eject")) {
      -            if (sdio) {
      -                sdio_mediachange(sdio, false);
      -                return OK;
      -            }
      -        }
      -        else if (!strcmp(argv[1], "status")) {
      -            printf("SDcard #%d Status:\n", slotno);
      -#ifndef CONFIG_MMCSD_HAVECARDDETECT
      -            printf("\t - Without SDcard detect capability\n");
      -#endif
      -            return 0;
      -        }
      -    }
      -  
      -    printf("%s:  {slotno}\n", argv[0]);
      -    return -1;
      -}
      diff --git a/apps/vsn/sysinfo/Kconfig b/apps/vsn/sysinfo/Kconfig
      deleted file mode 100644
      index 38e0f16be..000000000
      --- a/apps/vsn/sysinfo/Kconfig
      +++ /dev/null
      @@ -1,14 +0,0 @@
      -#
      -# For a description of the syntax of this configuration file,
      -# see misc/tools/kconfig-language.txt.
      -#
      -
      -config VSN_SYSINFO
      -	bool "NSH sysinfo command"
      -	default n
      -	---help---
      -		Enable support for the NSH sysinfo command.
      -
      -if VSN_SYSINFO
      -endif
      -
      diff --git a/apps/vsn/sysinfo/Makefile b/apps/vsn/sysinfo/Makefile
      deleted file mode 100644
      index b4afc8a97..000000000
      --- a/apps/vsn/sysinfo/Makefile
      +++ /dev/null
      @@ -1,114 +0,0 @@
      -############################################################################
      -# Makefile
      -#
      -#   Copyright (C) 2011 Uros Platise. All rights reserved.
      -#   Author: Uros Platise 
      -#           Gregory Nutt 
      -#
      -# 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.
      -#
      -############################################################################
      -
      -# TODO, this makefile should run make under the app dirs, instead of
      -# sourcing the Make.defs!
      -
      --include $(TOPDIR)/.config
      --include $(TOPDIR)/Make.defs
      -include $(APPDIR)/Make.defs
      -
      -ifeq ($(WINTOOL),y)
      -INCDIROPT	= -w
      -endif
      -
      -# Hello Application
      -# TODO: appname can be automatically extracted from the directory name
      -
      -APPNAME		= sysinfo
      -PRIORITY	= SCHED_PRIORITY_DEFAULT
      -STACKSIZE	= 768
      -
      -ASRCS		=
      -CSRCS		= sysinfo.c
      -
      -AOBJS		= $(ASRCS:.S=$(OBJEXT))
      -COBJS		= $(CSRCS:.c=$(OBJEXT))
      -
      -SRCS		= $(ASRCS) $(CSRCS)
      -OBJS		= $(AOBJS) $(COBJS)
      -
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      -else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      -endif
      -
      -ROOTDEPPATH	= --dep-path .
      -
      -# Common build
      -
      -VPATH		= 
      -
      -all:	.built
      -.PHONY: context depend clean distclean
      -
      -$(AOBJS): %$(OBJEXT): %.S
      -	$(call ASSEMBLE, $<, $@)
      -
      -$(COBJS): %$(OBJEXT): %.c
      -	$(call COMPILE, $<, $@)
      -
      -.built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      -	@touch .built
      -
      -# Register application
      -
      -.context:
      -	$(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main)
      -	@touch $@
      -
      -context: .context
      -
      -# Create dependencies
      -
      -.depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      -	@touch $@
      -
      -depend: .depend
      -
      -clean:
      -	@rm -f *.o *~ .*.swp .built
      -	$(call CLEAN)
      -
      -distclean: clean
      -	@rm -f .context Make.dep .depend
      -
      --include Make.dep
      diff --git a/apps/vsn/sysinfo/README.txt b/apps/vsn/sysinfo/README.txt
      deleted file mode 100644
      index 3792f4a59..000000000
      --- a/apps/vsn/sysinfo/README.txt
      +++ /dev/null
      @@ -1,6 +0,0 @@
      -
      -This application provides access to System Information
      -
      -	Source: NuttX
      -	Date: 15. April 2011
      -    Author: Uros Platise 
      diff --git a/apps/vsn/sysinfo/sysinfo.c b/apps/vsn/sysinfo/sysinfo.c
      deleted file mode 100644
      index 8625f9db7..000000000
      --- a/apps/vsn/sysinfo/sysinfo.c
      +++ /dev/null
      @@ -1,69 +0,0 @@
      -/****************************************************************************
      - * sysinfo/sysinfo.c
      - *
      - *   Copyright (C) 2011 Uros Platise. All rights reserved.
      - *   Author: Uros Platise 
      - *
      - * 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.
      - *
      - ****************************************************************************/
      - 
      -/** \file
      - *  \brief System Information
      - *  \author Uros Platise
      - * 
      - * Collects and reports system information.
      - * 
      - * \todo Gather information also from low-level devices, kernel/sched, clock,
      - *   and further reporting as: sysinfo rtc, or sysinfo sched, ... with 
      - *   sysinfo help to report all of the options.
      - *
      - **/
      -
      -#include 
      -#include 
      -#include 
      -
      -#include 
      -#include 
      -
      -
      -int sysinfo_main(int argc, char *argv[])
      -{
      -	printf("System Information:\n");
      -    
      -    printf("\tNuttX Version:\t" CONFIG_VERSION_STRING " Build: %d\n", CONFIG_VERSION_BUILD);
      -    
      -    printf("\tSystem Time:\t%d [s] UTC "
      -#ifdef CONFIG_RTC
      -        "Hardware RTC Support"
      -#endif
      -        "\n", time(NULL) );
      -
      -	return 0;
      -}
      diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html
      index 0370a708d..ec6a8be24 100644
      --- a/nuttx/Documentation/NuttX.html
      +++ b/nuttx/Documentation/NuttX.html
      @@ -497,7 +497,7 @@
         
           

    • - RAMDISK, pipes, FIFO, /dev/null, /dev/zero, and loop drivers. + RAMDISK, pipes, FIFO, /dev/null, /dev/zero, /dev/random, and loop drivers.
    • -- cgit v1.2.3 From e6656c077c35341384d5474f0d7b65067b7997ec Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 4 Oct 2012 00:11:05 +0000 Subject: Delete the apps/vsn directory (moved commands to apps/system) git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5209 42af7a65-404d-4744-a932-0658087f49c3 --- apps/system/i2c/Makefile | 2 +- apps/system/ramtron/ramtron.c | 2 +- apps/system/readline/readline.c | 2 +- nuttx/Documentation/README.html | 19 +++--- nuttx/README.txt | 5 +- nuttx/configs/compal_e88/nsh_highram/appconfig | 2 +- nuttx/configs/compal_e99/nsh_compalram/appconfig | 2 +- nuttx/configs/compal_e99/nsh_highram/appconfig | 2 +- nuttx/configs/fire-stm32v2/nsh/defconfig | 39 +++++++----- nuttx/configs/shenzhou/nsh/defconfig | 35 ++++++++--- nuttx/configs/shenzhou/nxwm/defconfig | 24 ++++--- nuttx/configs/stm3240g-eval/discover/defconfig | 79 +++++++++++++++++++----- nuttx/configs/stm3240g-eval/xmlrpc/defconfig | 69 ++++++++++++++++----- nuttx/configs/vsn/nsh/appconfig | 10 +-- 14 files changed, 209 insertions(+), 83 deletions(-) (limited to 'nuttx') diff --git a/apps/system/i2c/Makefile b/apps/system/i2c/Makefile index 845c149f6..00db91bb7 100644 --- a/apps/system/i2c/Makefile +++ b/apps/system/i2c/Makefile @@ -1,5 +1,5 @@ ############################################################################ -# apps/system/i2c +# apps/system/i2c/Makefile # # Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. # Author: Gregory Nutt diff --git a/apps/system/ramtron/ramtron.c b/apps/system/ramtron/ramtron.c index cd4012787..78773649c 100644 --- a/apps/system/ramtron/ramtron.c +++ b/apps/system/ramtron/ramtron.c @@ -1,5 +1,5 @@ /**************************************************************************** - * ramtron/ramtron.c + * apps/system/ramtron/ramtron.c * * Copyright (C) 2011 Uros Platise. All rights reserved. * Copyright (C) 2009 Gregory Nutt. All rights reserved. diff --git a/apps/system/readline/readline.c b/apps/system/readline/readline.c index ec2dc1c0a..f64049ed7 100644 --- a/apps/system/readline/readline.c +++ b/apps/system/readline/readline.c @@ -1,5 +1,5 @@ /**************************************************************************** - * lib/stdio/lib_fgets.c + * apps/system/readline/readline.c * * Copyright (C) 2007-2008, 2011-2012 Gregory Nutt. All rights reserved. * Author: Gregory Nutt diff --git a/nuttx/Documentation/README.html b/nuttx/Documentation/README.html index 95102a004..4d87f55a6 100644 --- a/nuttx/Documentation/README.html +++ b/nuttx/Documentation/README.html @@ -265,16 +265,15 @@ | `- README.txt |- NxWidgets/ | `- README.txt - |- system/ - | |- i2c/README.txt - | |- free/README.txt - | `- install/README.txt - `- vsn/ - |- poweroff/README.txt - |- ramtron/README.txt - |- sdcard/README.txt - |- sysinfo/README.txt - `- README.txt + `- system/ + |- i2c/README.txt + |- free/README.txt + |- install/README.txt + |- poweroff/README.txt + |- ramtron/README.txt + |- sdcard/README.txt + |- sysinfo/README.txt + `- README.txt
    diff --git a/nuttx/README.txt b/nuttx/README.txt index 7477e0a24..d60da2d88 100644 --- a/nuttx/README.txt +++ b/nuttx/README.txt @@ -853,9 +853,8 @@ apps |- system/ | |- i2c/README.txt | |- free/README.txt - | `- install - | `- README.txt - |- vsn/ + | |- install + | | `- README.txt | |- poweroff | | `- README.txt | |- ramtron diff --git a/nuttx/configs/compal_e88/nsh_highram/appconfig b/nuttx/configs/compal_e88/nsh_highram/appconfig index 00921c361..4d12335c7 100644 --- a/nuttx/configs/compal_e88/nsh_highram/appconfig +++ b/nuttx/configs/compal_e88/nsh_highram/appconfig @@ -40,4 +40,4 @@ CONFIGURED_APPS += nshlib # Path to example in apps/examples CONFIGURED_APPS += examples/hello -CONFIGURED_APPS += vsn/poweroff +CONFIGURED_APPS += system/poweroff diff --git a/nuttx/configs/compal_e99/nsh_compalram/appconfig b/nuttx/configs/compal_e99/nsh_compalram/appconfig index 8df90adb0..e351d3366 100644 --- a/nuttx/configs/compal_e99/nsh_compalram/appconfig +++ b/nuttx/configs/compal_e99/nsh_compalram/appconfig @@ -40,4 +40,4 @@ CONFIGURED_APPS += examples/nsh # Path to example in apps/examples CONFIGURED_APPS += examples/hello -CONFIGURED_APPS += vsn/poweroff +CONFIGURED_APPS += system/poweroff diff --git a/nuttx/configs/compal_e99/nsh_highram/appconfig b/nuttx/configs/compal_e99/nsh_highram/appconfig index 241253f8c..db5e61236 100644 --- a/nuttx/configs/compal_e99/nsh_highram/appconfig +++ b/nuttx/configs/compal_e99/nsh_highram/appconfig @@ -41,7 +41,7 @@ CONFIGURED_APPS += nshlib # Path to example in apps/examples #CONFIGURED_APPS += examples/hello #fails not finding hello_main despite of good config -CONFIGURED_APPS += vsn/poweroff +CONFIGURED_APPS += system/poweroff CONFIGURED_APPS += examples/ostest CONFIGURED_APPS += examples/nxtext CONFIGURED_APPS += examples/nxhello diff --git a/nuttx/configs/fire-stm32v2/nsh/defconfig b/nuttx/configs/fire-stm32v2/nsh/defconfig index d6aaae05a..25e782dfe 100644 --- a/nuttx/configs/fire-stm32v2/nsh/defconfig +++ b/nuttx/configs/fire-stm32v2/nsh/defconfig @@ -133,7 +133,6 @@ CONFIG_STM32_PWR=y CONFIG_STM32_SDIO=y CONFIG_STM32_SPI1=y # CONFIG_STM32_SPI2 is not set -# CONFIG_STM32_SPI4 is not set # CONFIG_STM32_TIM1 is not set # CONFIG_STM32_TIM2 is not set # CONFIG_STM32_TIM3 is not set @@ -189,11 +188,6 @@ CONFIG_SDIO_PRI=128 CONFIG_SDIO_DMAPRIO=0x00001000 # CONFIG_SDIO_WIDTH_D1_ONLY is not set -# -# Ethernet MAC configuration -# -CONFIG_STM32_PHYADDR=1 - # # USB Host Configuration # @@ -496,6 +490,11 @@ CONFIG_FAT_MAXFNAME=32 # # CONFIG_SYSLOG is not set +# +# Graphics Support +# +# CONFIG_NX is not set + # # Memory Management # @@ -974,12 +973,16 @@ CONFIG_NSH_DRIPADDR=0x0a000001 CONFIG_NSH_NETMASK=0xffffff00 CONFIG_NSH_NOMAC=y +# +# NxWidgets/NxWM +# + # # System NSH Add-Ons # # -# Custom free memory command +# Custom Free Memory Command # # CONFIG_SYSTEM_FREE is not set @@ -1001,19 +1004,27 @@ CONFIG_I2CTOOL_DEFFREQ=100000 # CONFIG_SYSTEM_INSTALL is not set # -# readline() support +# readline() # CONFIG_SYSTEM_READLINE=y CONFIG_READLINE_ECHO=y # -# VSN board Add-Ons +# Power Off +# +# CONFIG_SYSTEM_POWEROFF is not set + +# +# RAMTRON +# +# CONFIG_SYSTEM_RAMTRON is not set + +# +# SD Card # +# CONFIG_SYSTEM_SDCARD is not set # -# VSN board add-ons +# Sysinfo # -# CONFIG_VSN_POWEROFF is not set -# CONFIG_VSN_RAMTRON is not set -# CONFIG_VSN_SDCARD is not set -# CONFIG_VSN_SYSINFO is not set +# CONFIG_SYSTEM_SYSINFO is not set diff --git a/nuttx/configs/shenzhou/nsh/defconfig b/nuttx/configs/shenzhou/nsh/defconfig index 706881cc0..21b7fcf90 100644 --- a/nuttx/configs/shenzhou/nsh/defconfig +++ b/nuttx/configs/shenzhou/nsh/defconfig @@ -132,7 +132,7 @@ CONFIG_STM32_ETHMAC=y CONFIG_STM32_PWR=y CONFIG_STM32_SPI1=y # CONFIG_STM32_SPI2 is not set -# CONFIG_STM32_SPI4 is not set +# CONFIG_STM32_SPI3 is not set # CONFIG_STM32_TIM1 is not set # CONFIG_STM32_TIM2 is not set # CONFIG_STM32_TIM3 is not set @@ -433,6 +433,11 @@ CONFIG_FAT_MAXFNAME=32 # # CONFIG_SYSLOG is not set +# +# Graphics Support +# +# CONFIG_NX is not set + # # Memory Management # @@ -895,12 +900,16 @@ CONFIG_NSH_DRIPADDR=0x0a000001 CONFIG_NSH_NETMASK=0xffffff00 CONFIG_NSH_NOMAC=y +# +# NxWidgets/NxWM +# + # # System NSH Add-Ons # # -# Custom free memory command +# Custom Free Memory Command # # CONFIG_SYSTEM_FREE is not set @@ -914,19 +923,27 @@ CONFIG_NSH_NOMAC=y # CONFIG_SYSTEM_INSTALL is not set # -# readline() support +# readline() # CONFIG_SYSTEM_READLINE=y CONFIG_READLINE_ECHO=y # -# VSN board Add-Ons +# Power Off +# +# CONFIG_SYSTEM_POWEROFF is not set + +# +# RAMTRON +# +# CONFIG_SYSTEM_RAMTRON is not set + +# +# SD Card # +# CONFIG_SYSTEM_SDCARD is not set # -# VSN board add-ons +# Sysinfo # -# CONFIG_VSN_POWEROFF is not set -# CONFIG_VSN_RAMTRON is not set -# CONFIG_VSN_SDCARD is not set -# CONFIG_VSN_SYSINFO is not set +# CONFIG_SYSTEM_SYSINFO is not set diff --git a/nuttx/configs/shenzhou/nxwm/defconfig b/nuttx/configs/shenzhou/nxwm/defconfig index 1b21fbd1b..0bdc9f45c 100644 --- a/nuttx/configs/shenzhou/nxwm/defconfig +++ b/nuttx/configs/shenzhou/nxwm/defconfig @@ -1159,7 +1159,7 @@ CONFIG_NXWM_HEXCALCULATOR_FONTID=5 # # -# Custom free memory command +# Custom Free Memory Command # # CONFIG_SYSTEM_FREE is not set @@ -1173,19 +1173,27 @@ CONFIG_NXWM_HEXCALCULATOR_FONTID=5 # CONFIG_SYSTEM_INSTALL is not set # -# readline() support +# readline() # CONFIG_SYSTEM_READLINE=y CONFIG_READLINE_ECHO=y # -# VSN board Add-Ons +# Power Off # +# CONFIG_SYSTEM_POWEROFF is not set # -# VSN board add-ons +# RAMTRON # -# CONFIG_VSN_POWEROFF is not set -# CONFIG_VSN_RAMTRON is not set -# CONFIG_VSN_SDCARD is not set -# CONFIG_VSN_SYSINFO is not set +# CONFIG_SYSTEM_RAMTRON is not set + +# +# SD Card +# +# CONFIG_SYSTEM_SDCARD is not set + +# +# Sysinfo +# +# CONFIG_SYSTEM_SYSINFO is not set diff --git a/nuttx/configs/stm3240g-eval/discover/defconfig b/nuttx/configs/stm3240g-eval/discover/defconfig index 71dce1028..12075b891 100644 --- a/nuttx/configs/stm3240g-eval/discover/defconfig +++ b/nuttx/configs/stm3240g-eval/discover/defconfig @@ -36,17 +36,22 @@ CONFIG_RAW_BINARY=y CONFIG_DEBUG=y # CONFIG_DEBUG_VERBOSE is not set # CONFIG_DEBUG_ENABLE is not set + +# +# Subsystem Debug Options +# # CONFIG_DEBUG_SCHED is not set # CONFIG_DEBUG_MM is not set CONFIG_DEBUG_NET=y -# CONFIG_DEBUG_USB is not set # CONFIG_DEBUG_FS is not set # CONFIG_DEBUG_LIB is not set # CONFIG_DEBUG_BINFMT is not set # CONFIG_DEBUG_GRAPHICS is not set + +# +# Driver Debug Options +# # CONFIG_DEBUG_I2C is not set -# CONFIG_DEBUG_SPI is not set -# CONFIG_DEBUG_WATCHDOG is not set # CONFIG_DEBUG_SYMBOLS is not set # @@ -179,6 +184,7 @@ CONFIG_STM32_USART3=y # CONFIG_STM32_UART5 is not set # CONFIG_STM32_USART6 is not set # CONFIG_STM32_WWDG is not set +CONFIG_STM32_I2C=y # # Alternate Pin Mapping @@ -191,6 +197,15 @@ CONFIG_STM32_JTAG_FULL_ENABLE=y # CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set # CONFIG_STM32_CCMEXCLUDE is not set +# +# I2C Configuration +# +# CONFIG_STM32_I2C_DYNTIMEO is not set +CONFIG_STM32_I2CTIMEOSEC=0 +CONFIG_STM32_I2CTIMEOMS=500 +CONFIG_STM32_I2CTIMEOTICKS=500 +# CONFIG_STM32_I2C_DUTY16_9 is not set + # # Ethernet MAC configuration # @@ -198,13 +213,16 @@ CONFIG_STM32_PHYADDR=1 CONFIG_STM32_MII=y CONFIG_STM32_MII_MCO1=y # CONFIG_STM32_MII_MCO2 is not set +# CONFIG_STM32_MII_EXTCLK is not set CONFIG_STM32_AUTONEG=y CONFIG_STM32_PHYSR=16 +# CONFIG_STM32_PHYSR_ALTCONFIG is not set CONFIG_STM32_PHYSR_SPEED=0x0002 CONFIG_STM32_PHYSR_100MBPS=0x0000 CONFIG_STM32_PHYSR_MODE=0x0004 CONFIG_STM32_PHYSR_FULLDUPLEX=0x0004 # CONFIG_STM32_ETH_PTP is not set +# CONFIG_STM32_ETHMAC_REGDEBUG is not set # # USB Host Configuration @@ -223,7 +241,7 @@ CONFIG_ARCH_STACKDUMP=y CONFIG_DRAM_START=0x20000000 CONFIG_DRAM_SIZE=196608 CONFIG_ARCH_HAVE_INTERRUPTSTACK=y -# CONFIG_ARCH_INTERRUPTSTACK is not set +CONFIG_ARCH_INTERRUPTSTACK=0 # # Boot options @@ -326,6 +344,8 @@ CONFIG_I2C_TRANSFER=y # CONFIG_I2C_WRITEREAD is not set CONFIG_I2C_POLLED=y # CONFIG_I2C_TRACE is not set +CONFIG_ARCH_HAVE_I2CRESET=y +# CONFIG_I2C_RESET is not set # CONFIG_SPI is not set # CONFIG_RTC is not set # CONFIG_WATCHDOG is not set @@ -377,6 +397,11 @@ CONFIG_USART3_2STOP=0 # Networking Support # CONFIG_NET=y +CONFIG_ARCH_HAVE_PHY=y +# CONFIG_PHY_KS8721 is not set +CONFIG_PHY_DP83848C=y +# CONFIG_PHY_LAN8720 is not set +# CONFIG_PHY_DM9161 is not set # CONFIG_NET_NOINTS is not set CONFIG_NET_MULTIBUFFER=y # CONFIG_NET_IPv6 is not set @@ -388,7 +413,7 @@ CONFIG_NET_BUFSIZE=650 CONFIG_NET_TCP=y CONFIG_NET_TCP_CONNS=40 CONFIG_NET_MAX_LISTENPORTS=40 -# CONFIG_NET_TCP_READAHEAD_BUFSIZE=562 +# CONFIG_NET_TCP_READAHEAD_BUFSIZE=650 CONFIG_NET_NTCP_READAHEAD_BUFFERS=16 CONFIG_NET_TCP_RECVDELAY=0 CONFIG_NET_TCPBACKLOG=y @@ -401,7 +426,7 @@ CONFIG_NET_ICMP_PING=y # CONFIG_NET_PINGADDRCONF is not set # CONFIG_NET_IGMP is not set CONFIG_NET_STATISTICS=y -# CONFIG_NET_RECEIVE_WINDOW=562 +# CONFIG_NET_RECEIVE_WINDOW=650 CONFIG_NET_ARPTAB_SIZE=16 CONFIG_NET_ARP_IPIN=y @@ -428,6 +453,11 @@ CONFIG_FAT_MAXFNAME=32 # # CONFIG_SYSLOG is not set +# +# Graphics Support +# +# CONFIG_NX is not set + # # Memory Management # @@ -725,6 +755,10 @@ CONFIG_EXAMPLE_DISCOVER_NETMASK=0xffffff00 # # CONFIG_EXAMPLES_WLAN is not set +# +# XML RPC Example +# + # # Interpreters # @@ -815,6 +849,11 @@ CONFIG_DISCOVER_INTERFACE="eth0" CONFIG_DISCOVER_DEVICE_CLASS=0xff CONFIG_CONFIG_DISCOVER_DESCR="STM3240G-EVAL" +# +# XML-RPC library +# +# CONFIG_NETUTILS_XMLRPC is not set + # # ModBus # @@ -829,12 +868,16 @@ CONFIG_CONFIG_DISCOVER_DESCR="STM3240G-EVAL" # # CONFIG_NSH_LIBRARY is not set +# +# NxWidgets/NxWM +# + # # System NSH Add-Ons # # -# Custom free memory command +# Custom Free Memory Command # # CONFIG_SYSTEM_FREE is not set @@ -849,18 +892,26 @@ CONFIG_CONFIG_DISCOVER_DESCR="STM3240G-EVAL" # CONFIG_SYSTEM_INSTALL is not set # -# readline() support +# readline() # # CONFIG_SYSTEM_READLINE is not set # -# VSN board Add-Ons +# Power Off +# +# CONFIG_SYSTEM_POWEROFF is not set + +# +# RAMTRON +# +# CONFIG_SYSTEM_RAMTRON is not set + +# +# SD Card # +# CONFIG_SYSTEM_SDCARD is not set # -# VSN board add-ons +# Sysinfo # -# CONFIG_VSN_POWEROFF is not set -# CONFIG_VSN_RAMTRON is not set -# CONFIG_VSN_SDCARD is not set -# CONFIG_VSN_SYSINFO is not set +# CONFIG_SYSTEM_SYSINFO is not set diff --git a/nuttx/configs/stm3240g-eval/xmlrpc/defconfig b/nuttx/configs/stm3240g-eval/xmlrpc/defconfig index cd80ea618..c2ba860fa 100644 --- a/nuttx/configs/stm3240g-eval/xmlrpc/defconfig +++ b/nuttx/configs/stm3240g-eval/xmlrpc/defconfig @@ -36,17 +36,22 @@ CONFIG_RAW_BINARY=y CONFIG_DEBUG=y # CONFIG_DEBUG_VERBOSE is not set # CONFIG_DEBUG_ENABLE is not set + +# +# Subsystem Debug Options +# # CONFIG_DEBUG_SCHED is not set # CONFIG_DEBUG_MM is not set CONFIG_DEBUG_NET=y -# CONFIG_DEBUG_USB is not set # CONFIG_DEBUG_FS is not set # CONFIG_DEBUG_LIB is not set # CONFIG_DEBUG_BINFMT is not set # CONFIG_DEBUG_GRAPHICS is not set + +# +# Driver Debug Options +# # CONFIG_DEBUG_I2C is not set -# CONFIG_DEBUG_SPI is not set -# CONFIG_DEBUG_WATCHDOG is not set # CONFIG_DEBUG_SYMBOLS is not set # @@ -179,6 +184,7 @@ CONFIG_STM32_USART3=y # CONFIG_STM32_UART5 is not set # CONFIG_STM32_USART6 is not set # CONFIG_STM32_WWDG is not set +CONFIG_STM32_I2C=y # # Alternate Pin Mapping @@ -191,6 +197,15 @@ CONFIG_STM32_JTAG_FULL_ENABLE=y # CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set # CONFIG_STM32_CCMEXCLUDE is not set +# +# I2C Configuration +# +# CONFIG_STM32_I2C_DYNTIMEO is not set +CONFIG_STM32_I2CTIMEOSEC=0 +CONFIG_STM32_I2CTIMEOMS=500 +CONFIG_STM32_I2CTIMEOTICKS=500 +# CONFIG_STM32_I2C_DUTY16_9 is not set + # # Ethernet MAC configuration # @@ -201,11 +216,13 @@ CONFIG_STM32_MII_MCO1=y # CONFIG_STM32_MII_EXTCLK is not set CONFIG_STM32_AUTONEG=y CONFIG_STM32_PHYSR=16 +# CONFIG_STM32_PHYSR_ALTCONFIG is not set CONFIG_STM32_PHYSR_SPEED=0x0002 CONFIG_STM32_PHYSR_100MBPS=0x0000 CONFIG_STM32_PHYSR_MODE=0x0004 CONFIG_STM32_PHYSR_FULLDUPLEX=0x0004 # CONFIG_STM32_ETH_PTP is not set +# CONFIG_STM32_ETHMAC_REGDEBUG is not set # # USB Host Configuration @@ -224,7 +241,7 @@ CONFIG_ARCH_STACKDUMP=y CONFIG_DRAM_START=0x20000000 CONFIG_DRAM_SIZE=196608 CONFIG_ARCH_HAVE_INTERRUPTSTACK=y -# CONFIG_ARCH_INTERRUPTSTACK is not set +CONFIG_ARCH_INTERRUPTSTACK=0 # # Boot options @@ -319,6 +336,8 @@ CONFIG_I2C_TRANSFER=y # CONFIG_I2C_WRITEREAD is not set CONFIG_I2C_POLLED=y # CONFIG_I2C_TRACE is not set +CONFIG_ARCH_HAVE_I2CRESET=y +# CONFIG_I2C_RESET is not set # CONFIG_SPI is not set # CONFIG_RTC is not set # CONFIG_WATCHDOG is not set @@ -371,6 +390,11 @@ CONFIG_USART3_2STOP=0 # Networking Support # CONFIG_NET=y +CONFIG_ARCH_HAVE_PHY=y +# CONFIG_PHY_KS8721 is not set +CONFIG_PHY_DP83848C=y +# CONFIG_PHY_LAN8720 is not set +# CONFIG_PHY_DM9161 is not set # CONFIG_NET_NOINTS is not set CONFIG_NET_MULTIBUFFER=y # CONFIG_NET_IPv6 is not set @@ -382,7 +406,7 @@ CONFIG_NET_BUFSIZE=650 CONFIG_NET_TCP=y CONFIG_NET_TCP_CONNS=40 CONFIG_NET_MAX_LISTENPORTS=40 -# CONFIG_NET_TCP_READAHEAD_BUFSIZE=562 +# CONFIG_NET_TCP_READAHEAD_BUFSIZE=650 CONFIG_NET_NTCP_READAHEAD_BUFFERS=16 CONFIG_NET_TCP_RECVDELAY=0 CONFIG_NET_TCPBACKLOG=y @@ -395,7 +419,7 @@ CONFIG_NET_ICMP_PING=y # CONFIG_NET_PINGADDRCONF is not set # CONFIG_NET_IGMP is not set CONFIG_NET_STATISTICS=y -# CONFIG_NET_RECEIVE_WINDOW=562 +# CONFIG_NET_RECEIVE_WINDOW=650 CONFIG_NET_ARPTAB_SIZE=16 CONFIG_NET_ARP_IPIN=y @@ -422,6 +446,11 @@ CONFIG_FAT_MAXFNAME=32 # # CONFIG_SYSLOG is not set +# +# Graphics Support +# +# CONFIG_NX is not set + # # Memory Management # @@ -829,12 +858,16 @@ CONFIG_XMLRPC_STRINGSIZE=64 # # CONFIG_NSH_LIBRARY is not set +# +# NxWidgets/NxWM +# + # # System NSH Add-Ons # # -# Custom free memory command +# Custom Free Memory Command # # CONFIG_SYSTEM_FREE is not set @@ -849,18 +882,26 @@ CONFIG_XMLRPC_STRINGSIZE=64 # CONFIG_SYSTEM_INSTALL is not set # -# readline() support +# readline() # # CONFIG_SYSTEM_READLINE is not set # -# VSN board Add-Ons +# Power Off +# +# CONFIG_SYSTEM_POWEROFF is not set + +# +# RAMTRON +# +# CONFIG_SYSTEM_RAMTRON is not set + +# +# SD Card # +# CONFIG_SYSTEM_SDCARD is not set # -# VSN board add-ons +# Sysinfo # -# CONFIG_VSN_POWEROFF is not set -# CONFIG_VSN_RAMTRON is not set -# CONFIG_VSN_SDCARD is not set -# CONFIG_VSN_SYSINFO is not set +# CONFIG_SYSTEM_SYSINFO is not set diff --git a/nuttx/configs/vsn/nsh/appconfig b/nuttx/configs/vsn/nsh/appconfig index a07059079..9b1e72bd4 100755 --- a/nuttx/configs/vsn/nsh/appconfig +++ b/nuttx/configs/vsn/nsh/appconfig @@ -53,19 +53,19 @@ CONFIGURED_APPS += nshlib # Individual selection of built-in applications: # Provide poweroff command to switch off the board -CONFIGURED_APPS += vsn/poweroff +CONFIGURED_APPS += system/poweroff # Provide SDcard tool -CONFIGURED_APPS += vsn/sdcard +CONFIGURED_APPS += system/sdcard # Provide RAMTRON tool -CONFIGURED_APPS += vsn/ramtron +CONFIGURED_APPS += system/ramtron # Provide System Information Utilityu -CONFIGURED_APPS += vsn/sysinfo +CONFIGURED_APPS += system/sysinfo # Provide JAVA Virtual Machine (the Darjeeling JVM) -#CONFIGURED_APPS += vsn/jvm +#CONFIGURED_APPS += system/jvm # Provide UNIX style free CONFIGURED_APPS += system/free -- cgit v1.2.3 From b0eb4f3ccee248a2f70fab8ab1972ad4907a9e22 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 4 Oct 2012 15:07:06 +0000 Subject: Change order of includes in apps/Makefile; add clock frequencies to shenzhou, fire, and olimex-stm32 board.h files git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5210 42af7a65-404d-4744-a932-0658087f49c3 --- apps/ChangeLog.txt | 5 +++++ apps/Makefile | 6 ++++-- nuttx/ChangeLog | 3 +++ nuttx/arch/arm/src/stm32/stm32_eth.c | 2 +- nuttx/configs/fire-stm32v2/include/board.h | 11 ++++++++++- nuttx/configs/olimex-stm32-p107/include/board.h | 11 ++++++++++- nuttx/configs/shenzhou/include/board.h | 11 ++++++++++- 7 files changed, 43 insertions(+), 6 deletions(-) (limited to 'nuttx') diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index 2d7b2eb9f..0e63d183e 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -353,3 +353,8 @@ * vsn: Moved all NSH commands from vsn/ to system/. Deleted the vsn/ directory. + * Makefile: Change order of includes when CONFIG_NEWCONFIG=y. In + that case, namedapp must be included first so that the namedapp + context is established first. If the namedapp context is established + later, it will overwrite any existing namedapp_list.h and nameapp_proto.h + files. diff --git a/apps/Makefile b/apps/Makefile index d2b0ecdab..e407e2de8 100644 --- a/apps/Makefile +++ b/apps/Makefile @@ -46,7 +46,7 @@ APPDIR = ${shell pwd} # appears in this directory as .config) # SUBDIRS is the list of all directories containing Makefiles. It is used # only for cleaning. namedapp must always be the first in the list. This -# list can be extended by the .config file as well +# list can be extended by the .config file as well. CONFIGURED_APPS = SUBDIRS = examples graphics interpreters modbus namedapp nshlib netutils system @@ -70,11 +70,13 @@ SUBDIRS = examples graphics interpreters modbus namedapp nshlib netutils system ifeq ($(CONFIG_NUTTX_NEWCONFIG),y) +# namedapp/Make.defs must be included first + +include namedapp/Make.defs include examples/Make.defs include graphics/Make.defs include interpreters/Make.defs include modbus/Make.defs -include namedapp/Make.defs include netutils/Make.defs include nshlib/Make.defs include system/Make.defs diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 55a06aeec..4ea03f34f 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3458,3 +3458,6 @@ * arch/arm/src/stm32/stm32_rng.c, chip/stm32_rng.h, and other files: Implementation of /dev/random using the STM32 Random Number Generator (RNG). + * board.h file for shenzhou, fire-stm32v2, and olimex-stm32-p107: + Add frequencies for HSE, HSI, LSE, and LSI. These are needed + by the STM32 watchdog driver. diff --git a/nuttx/arch/arm/src/stm32/stm32_eth.c b/nuttx/arch/arm/src/stm32/stm32_eth.c index 81345fabf..13f02679f 100644 --- a/nuttx/arch/arm/src/stm32/stm32_eth.c +++ b/nuttx/arch/arm/src/stm32/stm32_eth.c @@ -1956,7 +1956,7 @@ static void stm32_polltimer(int argc, uint32_t arg, ...) /* Check if the next TX descriptor is owned by the Ethernet DMA or CPU. We * cannot perform the timer poll if we are unable to accept another packet * for transmission. Hmmm.. might be bug here. Does this mean if there is - * a transmit in progress, we will missing TCP time state updates? + * a transmit in progress, we will miss TCP time state updates? * * In a race condition, ETH_TDES0_OWN may be cleared BUT still not available * because stm32_freeframe() has not yet run. If stm32_freeframe() has run, diff --git a/nuttx/configs/fire-stm32v2/include/board.h b/nuttx/configs/fire-stm32v2/include/board.h index 9a5d309ab..acd70933a 100644 --- a/nuttx/configs/fire-stm32v2/include/board.h +++ b/nuttx/configs/fire-stm32v2/include/board.h @@ -55,10 +55,19 @@ /* Clocking *************************************************************************/ -/* On-board crystal frequency is 8MHz (HSE) */ +/* HSI - 8 MHz RC factory-trimmed + * LSI - 40 KHz RC (30-60KHz, uncalibrated) + * HSE - On-board crystal frequency is 8MHz + * LSE - 32.768 kHz crytal + */ #define STM32_BOARD_XTAL 8000000ul +#define STM32_HSI_FREQUENCY 8000000ul +#define STM32_LSI_FREQUENCY 40000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL +#define STM32_LSE_FREQUENCY 32768 + /* PLL source is HSE/1, PLL multipler is 9: PLL frequency is 8MHz (XTAL) x 9 = 72MHz */ #define STM32_CFGR_PLLSRC RCC_CFGR_PLLSRC diff --git a/nuttx/configs/olimex-stm32-p107/include/board.h b/nuttx/configs/olimex-stm32-p107/include/board.h index ce0c82472..96051e25c 100644 --- a/nuttx/configs/olimex-stm32-p107/include/board.h +++ b/nuttx/configs/olimex-stm32-p107/include/board.h @@ -55,10 +55,19 @@ /* Clocking *************************************************************************/ -/* On-board crystal frequency is 25MHz (HSE) */ +/* HSI - 8 MHz RC factory-trimmed + * LSI - 40 KHz RC (30-60KHz, uncalibrated) + * HSE - On-board crystal frequency is 25MHz + * LSE - 32.768 kHz + */ #define STM32_BOARD_XTAL 25000000ul +#define STM32_HSI_FREQUENCY 8000000ul +#define STM32_LSI_FREQUENCY 40000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL +#define STM32_LSE_FREQUENCY 32768 + /* PLL ouput is 72MHz */ #define STM32_PLL_PREDIV2 RCC_CFGR2_PREDIV2d5 /* 25MHz / 5 => 5MHz */ diff --git a/nuttx/configs/shenzhou/include/board.h b/nuttx/configs/shenzhou/include/board.h index c105d4ab5..2897ac219 100644 --- a/nuttx/configs/shenzhou/include/board.h +++ b/nuttx/configs/shenzhou/include/board.h @@ -55,10 +55,19 @@ /* Clocking *************************************************************************/ -/* On-board crystal frequency is 25MHz (HSE) */ +/* HSI - 8 MHz RC factory-trimmed + * LSI - 40 KHz RC (30-60KHz, uncalibrated) + * HSE - On-board crystal frequency is 25MHz + * LSE - 32.768 kHz + */ #define STM32_BOARD_XTAL 25000000ul +#define STM32_HSI_FREQUENCY 8000000ul +#define STM32_LSI_FREQUENCY 40000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL +#define STM32_LSE_FREQUENCY 32768 + /* PLL ouput is 72MHz */ #define STM32_PLL_PREDIV2 RCC_CFGR2_PREDIV2d5 /* 25MHz / 5 => 5MHz */ -- cgit v1.2.3 From 44a18f5361f2cd78d5f71584869cd087ab3dabf7 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 4 Oct 2012 17:36:07 +0000 Subject: Change all occurrences of CONFIG_EXAMPLE_ to CONFIG_EXAMPLES_ for consistency; fleshed out a few more Kconfig files git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5211 42af7a65-404d-4744-a932-0658087f49c3 --- apps/ChangeLog.txt | 4 + apps/examples/Make.defs | 2 +- apps/examples/README.txt | 110 ++++++++++----------- apps/examples/adc/Kconfig | 24 +++++ apps/examples/adc/adc_main.c | 14 ++- apps/examples/buttons/buttons_main.c | 88 ++++++++--------- apps/examples/dhcpd/target.c | 22 ++--- apps/examples/discover/Kconfig | 22 ++--- apps/examples/discover/discover_main.c | 22 ++--- apps/examples/ftpd/ftpd.h | 26 ++--- apps/examples/ftpd/ftpd_main.c | 10 +- apps/examples/igmp/igmp.c | 16 +-- apps/examples/nettest/Makefile | 16 +-- apps/examples/nettest/host.c | 2 +- apps/examples/nettest/nettest.c | 12 +-- apps/examples/nettest/nettest.h | 4 +- apps/examples/nettest/nettest_client.c | 14 +-- apps/examples/nettest/nettest_server.c | 4 +- apps/examples/poll/net_listener.c | 10 +- apps/examples/poll/net_reader.c | 10 +- apps/examples/sendmail/target.c | 46 ++++----- apps/examples/telnetd/shell.c | 10 +- apps/examples/telnetd/shell.h | 20 ++-- apps/examples/thttpd/thttpd_main.c | 10 +- apps/examples/udp/Makefile | 12 +-- apps/examples/udp/host.c | 2 +- apps/examples/udp/target.c | 8 +- apps/examples/udp/udp-client.c | 2 +- apps/examples/udp/udp-internal.h | 4 +- apps/examples/uip/uip_main.c | 20 ++-- apps/examples/wget/Kconfig | 24 +++++ apps/examples/wget/target.c | 24 ++--- apps/examples/wlan/wlan_main.c | 18 ++-- nuttx/ChangeLog | 2 + nuttx/Documentation/NuttXRelated.html | 1 + nuttx/arch/sim/src/up_tapdev.c | 2 +- nuttx/arch/sim/src/up_wpcap.c | 2 +- nuttx/configs/amber/hello/defconfig | 22 ++--- nuttx/configs/avr32dev1/nsh/defconfig | 22 ++--- nuttx/configs/avr32dev1/ostest/defconfig | 22 ++--- nuttx/configs/c5471evm/httpd/defconfig | 34 +++---- nuttx/configs/c5471evm/nettest/defconfig | 34 +++---- nuttx/configs/c5471evm/nsh/defconfig | 34 +++---- nuttx/configs/c5471evm/ostest/defconfig | 34 +++---- nuttx/configs/compal_e88/nsh_highram/defconfig | 34 +++---- nuttx/configs/compal_e99/nsh_compalram/defconfig | 34 +++---- nuttx/configs/compal_e99/nsh_highram/defconfig | 34 +++---- nuttx/configs/demo9s12ne64/ostest/defconfig | 22 ++--- nuttx/configs/ea3131/nsh/defconfig | 22 ++--- nuttx/configs/ea3131/ostest/defconfig | 22 ++--- nuttx/configs/ea3131/pgnsh/defconfig | 22 ++--- nuttx/configs/ea3131/usbserial/defconfig | 22 ++--- nuttx/configs/ea3131/usbstorage/defconfig | 22 ++--- nuttx/configs/ea3152/ostest/defconfig | 22 ++--- nuttx/configs/eagle100/httpd/defconfig | 30 +++--- nuttx/configs/eagle100/nettest/defconfig | 22 ++--- nuttx/configs/eagle100/nsh/defconfig | 22 ++--- nuttx/configs/eagle100/nxflat/defconfig | 22 ++--- nuttx/configs/eagle100/ostest/defconfig | 22 ++--- nuttx/configs/eagle100/thttpd/defconfig | 28 +++--- nuttx/configs/ekk-lm3s9b96/nsh/defconfig | 22 ++--- nuttx/configs/ekk-lm3s9b96/ostest/defconfig | 22 ++--- nuttx/configs/ez80f910200kitg/ostest/defconfig | 32 +++--- nuttx/configs/ez80f910200zco/dhcpd/defconfig | 48 ++++----- nuttx/configs/ez80f910200zco/httpd/defconfig | 48 ++++----- nuttx/configs/ez80f910200zco/nettest/defconfig | 40 ++++---- nuttx/configs/ez80f910200zco/nsh/defconfig | 40 ++++---- nuttx/configs/ez80f910200zco/ostest/defconfig | 40 ++++---- nuttx/configs/ez80f910200zco/poll/defconfig | 40 ++++---- nuttx/configs/fire-stm32v2/nsh/defconfig | 2 +- nuttx/configs/hymini-stm32v/buttons/defconfig | 46 ++++----- nuttx/configs/hymini-stm32v/nsh/defconfig | 22 ++--- nuttx/configs/hymini-stm32v/nx/defconfig | 22 ++--- nuttx/configs/hymini-stm32v/usbserial/defconfig | 22 ++--- nuttx/configs/hymini-stm32v/usbstorage/defconfig | 22 ++--- nuttx/configs/kwikstik-k40/ostest/defconfig | 22 ++--- nuttx/configs/lincoln60/nsh/defconfig | 22 ++--- nuttx/configs/lincoln60/ostest/defconfig | 46 ++++----- nuttx/configs/lm3s6432-s2e/nsh/defconfig | 22 ++--- nuttx/configs/lm3s6432-s2e/ostest/defconfig | 22 ++--- nuttx/configs/lm3s6965-ek/nsh/defconfig | 22 ++--- nuttx/configs/lm3s6965-ek/nx/defconfig | 22 ++--- nuttx/configs/lm3s6965-ek/ostest/defconfig | 22 ++--- nuttx/configs/lm3s8962-ek/nsh/defconfig | 22 ++--- nuttx/configs/lm3s8962-ek/nx/defconfig | 22 ++--- nuttx/configs/lm3s8962-ek/ostest/defconfig | 22 ++--- nuttx/configs/lpc4330-xplorer/nsh/defconfig | 32 +++--- nuttx/configs/lpc4330-xplorer/ostest/defconfig | 32 +++--- nuttx/configs/lpcxpresso-lpc1768/dhcpd/defconfig | 30 +++--- nuttx/configs/lpcxpresso-lpc1768/nsh/defconfig | 22 ++--- nuttx/configs/lpcxpresso-lpc1768/nx/defconfig | 22 ++--- nuttx/configs/lpcxpresso-lpc1768/ostest/defconfig | 22 ++--- nuttx/configs/lpcxpresso-lpc1768/thttpd/defconfig | 28 +++--- .../lpcxpresso-lpc1768/usbstorage/defconfig | 22 ++--- nuttx/configs/mbed/hidkbd/defconfig | 22 ++--- nuttx/configs/mbed/nsh/defconfig | 22 ++--- nuttx/configs/micropendous3/hello/defconfig | 22 ++--- nuttx/configs/mirtoo/nsh/defconfig | 22 ++--- nuttx/configs/mirtoo/nxffs/defconfig | 22 ++--- nuttx/configs/mirtoo/ostest/defconfig | 22 ++--- nuttx/configs/mx1ads/ostest/defconfig | 22 ++--- nuttx/configs/ne64badge/ostest/defconfig | 22 ++--- nuttx/configs/ntosd-dm320/nettest/defconfig | 22 ++--- nuttx/configs/ntosd-dm320/nsh/defconfig | 22 ++--- nuttx/configs/ntosd-dm320/ostest/defconfig | 22 ++--- nuttx/configs/ntosd-dm320/poll/defconfig | 30 +++--- nuttx/configs/ntosd-dm320/thttpd/defconfig | 28 +++--- nuttx/configs/ntosd-dm320/udp/defconfig | 32 +++--- nuttx/configs/ntosd-dm320/uip/defconfig | 22 ++--- nuttx/configs/nucleus2g/nsh/defconfig | 22 ++--- nuttx/configs/nucleus2g/ostest/defconfig | 22 ++--- nuttx/configs/nucleus2g/usbserial/defconfig | 22 ++--- nuttx/configs/nucleus2g/usbstorage/defconfig | 22 ++--- nuttx/configs/olimex-lpc1766stk/ftpc/defconfig | 52 +++++----- nuttx/configs/olimex-lpc1766stk/hidkbd/defconfig | 46 ++++----- nuttx/configs/olimex-lpc1766stk/nettest/defconfig | 46 ++++----- nuttx/configs/olimex-lpc1766stk/nsh/defconfig | 46 ++++----- nuttx/configs/olimex-lpc1766stk/nx/defconfig | 46 ++++----- nuttx/configs/olimex-lpc1766stk/ostest/defconfig | 46 ++++----- .../configs/olimex-lpc1766stk/slip-httpd/defconfig | 52 +++++----- nuttx/configs/olimex-lpc1766stk/thttpd/defconfig | 52 +++++----- .../configs/olimex-lpc1766stk/usbserial/defconfig | 46 ++++----- .../configs/olimex-lpc1766stk/usbstorage/defconfig | 46 ++++----- nuttx/configs/olimex-lpc1766stk/wlan/defconfig | 32 +++--- nuttx/configs/olimex-stm32-p107/nsh/defconfig | 22 ++--- nuttx/configs/olimex-stm32-p107/ostest/defconfig | 22 ++--- nuttx/configs/olimex-strp711/nettest/defconfig | 14 +-- nuttx/configs/pcblogic-pic32mx/nsh/defconfig | 22 ++--- nuttx/configs/pcblogic-pic32mx/ostest/defconfig | 22 ++--- nuttx/configs/pic32-starterkit/nsh/defconfig | 22 ++--- nuttx/configs/pic32-starterkit/nsh2/defconfig | 22 ++--- nuttx/configs/pic32-starterkit/ostest/defconfig | 22 ++--- nuttx/configs/pic32mx7mmb/nsh/defconfig | 22 ++--- nuttx/configs/pic32mx7mmb/ostest/defconfig | 22 ++--- nuttx/configs/qemu-i486/nsh/defconfig | 22 ++--- nuttx/configs/qemu-i486/ostest/defconfig | 22 ++--- nuttx/configs/rgmp/arm/default/defconfig | 22 ++--- nuttx/configs/rgmp/arm/nsh/defconfig | 22 ++--- nuttx/configs/rgmp/x86/default/defconfig | 22 ++--- nuttx/configs/rgmp/x86/nsh/defconfig | 22 ++--- nuttx/configs/sam3u-ek/knsh/defconfig | 22 ++--- nuttx/configs/sam3u-ek/nsh/defconfig | 22 ++--- nuttx/configs/sam3u-ek/nx/defconfig | 22 ++--- nuttx/configs/sam3u-ek/ostest/defconfig | 22 ++--- nuttx/configs/sam3u-ek/touchscreen/defconfig | 22 ++--- nuttx/configs/shenzhou/nsh/defconfig | 2 +- nuttx/configs/shenzhou/nxwm/defconfig | 2 +- nuttx/configs/sim/README.txt | 2 +- nuttx/configs/sim/mount/defconfig | 22 ++--- nuttx/configs/sim/nettest/defconfig | 22 ++--- nuttx/configs/sim/nsh/defconfig | 22 ++--- nuttx/configs/sim/nsh2/defconfig | 22 ++--- nuttx/configs/sim/nx/defconfig | 22 ++--- nuttx/configs/sim/nx11/defconfig | 22 ++--- nuttx/configs/sim/nxffs/defconfig | 22 ++--- nuttx/configs/sim/nxwm/defconfig | 22 ++--- nuttx/configs/sim/ostest/defconfig | 22 ++--- nuttx/configs/sim/pashello/defconfig | 22 ++--- nuttx/configs/sim/touchscreen/defconfig | 22 ++--- nuttx/configs/skp16c26/ostest/defconfig | 22 ++--- nuttx/configs/stm3210e-eval/RIDE/defconfig | 22 ++--- nuttx/configs/stm3210e-eval/buttons/defconfig | 46 ++++----- nuttx/configs/stm3210e-eval/composite/defconfig | 22 ++--- nuttx/configs/stm3210e-eval/nsh/defconfig | 22 ++--- nuttx/configs/stm3210e-eval/nsh2/defconfig | 22 ++--- nuttx/configs/stm3210e-eval/nx/defconfig | 22 ++--- nuttx/configs/stm3210e-eval/nxconsole/defconfig | 22 ++--- nuttx/configs/stm3210e-eval/nxlines/defconfig | 22 ++--- nuttx/configs/stm3210e-eval/nxtext/defconfig | 22 ++--- nuttx/configs/stm3210e-eval/ostest/defconfig | 22 ++--- nuttx/configs/stm3210e-eval/pm/defconfig | 42 ++++---- nuttx/configs/stm3210e-eval/usbserial/defconfig | 22 ++--- nuttx/configs/stm3210e-eval/usbstorage/defconfig | 22 ++--- nuttx/configs/stm3220g-eval/README.txt | 10 +- nuttx/configs/stm3220g-eval/dhcpd/defconfig | 30 +++--- nuttx/configs/stm3220g-eval/nettest/defconfig | 22 ++--- nuttx/configs/stm3220g-eval/nsh/defconfig | 22 ++--- nuttx/configs/stm3220g-eval/nsh2/defconfig | 22 ++--- nuttx/configs/stm3220g-eval/nxwm/defconfig | 22 ++--- nuttx/configs/stm3220g-eval/ostest/defconfig | 36 +++---- nuttx/configs/stm3220g-eval/telnetd/defconfig | 30 +++--- nuttx/configs/stm3240g-eval/README.txt | 18 ++-- nuttx/configs/stm3240g-eval/dhcpd/defconfig | 30 +++--- nuttx/configs/stm3240g-eval/discover/defconfig | 10 +- nuttx/configs/stm3240g-eval/nettest/defconfig | 22 ++--- nuttx/configs/stm3240g-eval/nsh/defconfig | 22 ++--- nuttx/configs/stm3240g-eval/nsh2/defconfig | 22 ++--- nuttx/configs/stm3240g-eval/nxconsole/defconfig | 22 ++--- nuttx/configs/stm3240g-eval/nxwm/defconfig | 22 ++--- nuttx/configs/stm3240g-eval/ostest/defconfig | 36 +++---- nuttx/configs/stm3240g-eval/telnetd/defconfig | 30 +++--- nuttx/configs/stm3240g-eval/webserver/defconfig | 24 ++--- nuttx/configs/stm3240g-eval/xmlrpc/defconfig | 2 +- nuttx/configs/stm32f4discovery/nsh/defconfig | 22 ++--- nuttx/configs/stm32f4discovery/nxlines/defconfig | 22 ++--- nuttx/configs/stm32f4discovery/ostest/defconfig | 36 +++---- nuttx/configs/stm32f4discovery/pm/defconfig | 22 ++--- nuttx/configs/sure-pic32mx/nsh/defconfig | 22 ++--- nuttx/configs/sure-pic32mx/ostest/defconfig | 22 ++--- nuttx/configs/sure-pic32mx/usbnsh/defconfig | 22 ++--- nuttx/configs/teensy/hello/defconfig | 22 ++--- nuttx/configs/teensy/nsh/defconfig | 22 ++--- nuttx/configs/teensy/usbstorage/defconfig | 22 ++--- nuttx/configs/twr-k60n512/nsh/defconfig | 22 ++--- nuttx/configs/twr-k60n512/ostest/defconfig | 22 ++--- nuttx/configs/ubw32/nsh/defconfig | 22 ++--- nuttx/configs/ubw32/ostest/defconfig | 22 ++--- nuttx/configs/vsn/nsh/defconfig | 22 ++--- 208 files changed, 2527 insertions(+), 2464 deletions(-) (limited to 'nuttx') diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index 0e63d183e..397ccdac4 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -358,3 +358,7 @@ context is established first. If the namedapp context is established later, it will overwrite any existing namedapp_list.h and nameapp_proto.h files. + * CONFIG_EXAMPLES_*: To make things consistent, changed all occurrences + of CONFIG_EXAMPLE_* to CONFIG_EXAMPLES_*. + * Kconfig: Fleshed out apps/examples/adc/Kconfig and apps/examples/wget/Kconfig. + There are still a LOT of empty, stub Kconfig files. diff --git a/apps/examples/Make.defs b/apps/examples/Make.defs index e6b1f3ca3..d03b976d2 100644 --- a/apps/examples/Make.defs +++ b/apps/examples/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_EXAMPLES_DHCPD),y) CONFIGURED_APPS += examples/dhcpd endif -ifeq ($(CONFIG_EXAMPLE_DISCOVER),y) +ifeq ($(CONFIG_EXAMPLES_DISCOVER),y) CONFIGURED_APPS += examples/discover endif diff --git a/apps/examples/README.txt b/apps/examples/README.txt index 12d6d3892..7ef51025f 100644 --- a/apps/examples/README.txt +++ b/apps/examples/README.txt @@ -61,19 +61,19 @@ examples/buttons specific button interfaces. Configuration options: CONFIG_ARCH_BUTTONS - Must be defined for button support - CONFIG_EXAMPLE_BUTTONS_MIN - Lowest button number (MIN=0) - CONFIG_EXAMPLE_BUTTONS_MAX - Highest button number (MAX=7) + CONFIG_EXAMPLES_BUTTONS_MIN - Lowest button number (MIN=0) + CONFIG_EXAMPLES_BUTTONS_MAX - Highest button number (MAX=7) CONFIG_ARCH_IRQBUTTONS - Must be defined for interrupting button support - CONFIG_EXAMPLE_IRQBUTTONS_MIN - Lowest interrupting button number (MIN=0) - CONFIG_EXAMPLE_IRQBUTTONS_MAX - Highest interrupting button number (MAX=7) + CONFIG_EXAMPLES_IRQBUTTONS_MIN - Lowest interrupting button number (MIN=0) + CONFIG_EXAMPLES_IRQBUTTONS_MAX - Highest interrupting button number (MAX=7) Name strings for buttons: - CONFIG_EXAMPLE_BUTTONS_NAME0, CONFIG_EXAMPLE_BUTTONS_NAME1, - CONFIG_EXAMPLE_BUTTONS_NAME2, CONFIG_EXAMPLE_BUTTONS_NAME3, - CONFIG_EXAMPLE_BUTTONS_NAME4, CONFIG_EXAMPLE_BUTTONS_NAME5, - CONFIG_EXAMPLE_BUTTONS_NAME6, CONFIG_EXAMPLE_BUTTONS_NAME7, + CONFIG_EXAMPLES_BUTTONS_NAME0, CONFIG_EXAMPLES_BUTTONS_NAME1, + CONFIG_EXAMPLES_BUTTONS_NAME2, CONFIG_EXAMPLES_BUTTONS_NAME3, + CONFIG_EXAMPLES_BUTTONS_NAME4, CONFIG_EXAMPLES_BUTTONS_NAME5, + CONFIG_EXAMPLES_BUTTONS_NAME6, CONFIG_EXAMPLES_BUTTONS_NAME7, Additional architecture-/board- specific configuration settings may also be required. @@ -260,10 +260,10 @@ examples/dhcpd configuration settings) CONFIG_NET_BROADCAST=y - UDP broadcast support is needed. - CONFIG_EXAMPLE_DHCPD_NOMAC - (May be defined to use software assigned MAC) - CONFIG_EXAMPLE_DHCPD_IPADDR - Target IP address - CONFIG_EXAMPLE_DHCPD_DRIPADDR - Default router IP addess - CONFIG_EXAMPLE_DHCPD_NETMASK - Network mask + CONFIG_EXAMPLES_DHCPD_NOMAC - (May be defined to use software assigned MAC) + CONFIG_EXAMPLES_DHCPD_IPADDR - Target IP address + CONFIG_EXAMPLES_DHCPD_DRIPADDR - Default router IP addess + CONFIG_EXAMPLES_DHCPD_NETMASK - Network mask See also CONFIG_NETUTILS_DHCPD_* settings described elsewhere and used in netutils/dhcpd/dhcpd.c. These settings are required @@ -291,11 +291,11 @@ examples/discover NuttX configuration settings: - CONFIG_EXAMPLE_DISCOVER_DHCPC - DHCP Client - CONFIG_EXAMPLE_DISCOVER_NOMAC - Use canned MAC address - CONFIG_EXAMPLE_DISCOVER_IPADDR - Target IP address - CONFIG_EXAMPLE_DISCOVER_DRIPADDR - Router IP address - CONFIG_EXAMPLE_DISCOVER_NETMASK - Network Mask + CONFIG_EXAMPLES_DISCOVER_DHCPC - DHCP Client + CONFIG_EXAMPLES_DISCOVER_NOMAC - Use canned MAC address + CONFIG_EXAMPLES_DISCOVER_IPADDR - Target IP address + CONFIG_EXAMPLES_DISCOVER_DRIPADDR - Router IP address + CONFIG_EXAMPLES_DISCOVER_NETMASK - Network Mask examples/ftpc ^^^^^^^^^^^^^ @@ -367,12 +367,12 @@ examples/ftpd If CONFIG_EXAMPLES_FTPD_NONETINIT is not defined, then the following may be specified to customized the network configuration: - CONFIG_EXAMPLE_FTPD_NOMAC - If the hardware has no MAC address of its + CONFIG_EXAMPLES_FTPD_NOMAC - If the hardware has no MAC address of its own, define this =y to provide a bogus address for testing. - CONFIG_EXAMPLE_FTPD_IPADDR - The target IP address. Default 10.0.0.2 - CONFIG_EXAMPLE_FTPD_DRIPADDR - The default router address. Default + CONFIG_EXAMPLES_FTPD_IPADDR - The target IP address. Default 10.0.0.2 + CONFIG_EXAMPLES_FTPD_DRIPADDR - The default router address. Default 10.0.0.1 - CONFIG_EXAMPLE_FTPD_NETMASK - The network mask. Default: 255.255.255.0 + CONFIG_EXAMPLES_FTPD_NETMASK - The network mask. Default: 255.255.255.0 Other required configuration settings: Of course TCP networking support is required. But here are a couple that are less obvious: @@ -465,15 +465,15 @@ examples/igmp does not do much of value -- Much more is needed in order to verify the IGMP features! - * CONFIG_EXAMPLE_IGMP_NOMAC + * CONFIG_EXAMPLES_IGMP_NOMAC Set if the hardware has no MAC address; one will be assigned - * CONFIG_EXAMPLE_IGMP_IPADDR + * CONFIG_EXAMPLES_IGMP_IPADDR Target board IP address - * CONFIG_EXAMPLE_IGMP_DRIPADDR + * CONFIG_EXAMPLES_IGMP_DRIPADDR Default router address - * CONFIG_EXAMPLE_IGMP_NETMASK + * CONFIG_EXAMPLES_IGMP_NETMASK Network mask - * CONFIG_EXAMPLE_IGMP_GRPADDR + * CONFIG_EXAMPLES_IGMP_GRPADDR Multicast group address Applications using this example will need to provide an appconfig @@ -1023,10 +1023,10 @@ examples/poll CONFIG_NSOCKET_DESCRIPTORS - Defined to be greater than 0 CONFIG_NET_NTCP_READAHEAD_BUFFERS - Defined to be greater than zero - CONFIG_EXAMPLE_POLL_NOMAC - (May be defined to use software assigned MAC) - CONFIG_EXAMPLE_POLL_IPADDR - Target IP address - CONFIG_EXAMPLE_POLL_DRIPADDR - Default router IP addess - CONFIG_EXAMPLE_POLL_NETMASK - Network mask + CONFIG_EXAMPLES_POLL_NOMAC - (May be defined to use software assigned MAC) + CONFIG_EXAMPLES_POLL_IPADDR - Target IP address + CONFIG_EXAMPLES_POLL_DRIPADDR - Default router IP addess + CONFIG_EXAMPLES_POLL_NETMASK - Network mask In order to for select to work with incoming connections, you must also select: @@ -1163,14 +1163,14 @@ examples/sendmail Settings unique to this example include: - CONFIG_EXAMPLE_SENDMAIL_NOMAC - May be defined to use software assigned MAC (optional) - CONFIG_EXAMPLE_SENDMAIL_IPADDR - Target IP address (required) - CONFIG_EXAMPLE_SENDMAIL_DRIPADDR - Default router IP addess (required) - CONFIG_EXAMPLE_SENDMAILT_NETMASK - Network mask (required) - CONFIG_EXAMPLE_SENDMAIL_RECIPIENT - The recipient of the email (required) - CONFIG_EXAMPLE_SENDMAIL_SENDER - Optional. Default: "nuttx-testing@example.com" - CONFIG_EXAMPLE_SENDMAIL_SUBJECT - Optional. Default: "Testing SMTP from NuttX" - CONFIG_EXAMPLE_SENDMAIL_BODY - Optional. Default: "Test message sent by NuttX" + CONFIG_EXAMPLES_SENDMAIL_NOMAC - May be defined to use software assigned MAC (optional) + CONFIG_EXAMPLES_SENDMAIL_IPADDR - Target IP address (required) + CONFIG_EXAMPLES_SENDMAIL_DRIPADDR - Default router IP addess (required) + CONFIG_EXAMPLES_SENDMAILT_NETMASK - Network mask (required) + CONFIG_EXAMPLES_SENDMAIL_RECIPIENT - The recipient of the email (required) + CONFIG_EXAMPLES_SENDMAIL_SENDER - Optional. Default: "nuttx-testing@example.com" + CONFIG_EXAMPLES_SENDMAIL_SUBJECT - Optional. Default: "Testing SMTP from NuttX" + CONFIG_EXAMPLES_SENDMAIL_BODY - Optional. Default: "Test message sent by NuttX" NOTE: This test has not been verified on the NuttX target environment. As of this writing, unit-tested in the Cygwin/Linux host environment. @@ -1213,12 +1213,12 @@ examples/telnetd Default: SCHED_PRIORITY_DEFAULT CONFIG_EXAMPLES_TELNETD_CLIENTSTACKSIZE - Stack size allocated for the Telnet client. Default: 2048 - CONFIG_EXAMPLE_TELNETD_NOMAC - If the hardware has no MAC address of its + CONFIG_EXAMPLES_TELNETD_NOMAC - If the hardware has no MAC address of its own, define this =y to provide a bogus address for testing. - CONFIG_EXAMPLE_TELNETD_IPADDR - The target IP address. Default 10.0.0.2 - CONFIG_EXAMPLE_TELNETD_DRIPADDR - The default router address. Default + CONFIG_EXAMPLES_TELNETD_IPADDR - The target IP address. Default 10.0.0.2 + CONFIG_EXAMPLES_TELNETD_DRIPADDR - The default router address. Default 10.0.0.1 - CONFIG_EXAMPLE_TELNETD_NETMASK - The network mask. Default: 255.255.255.0 + CONFIG_EXAMPLES_TELNETD_NETMASK - The network mask. Default: 255.255.255.0 The appconfig file (apps/.config) should include: @@ -1240,9 +1240,9 @@ examples/thttpd CGI programs. see configs/README.txt for most THTTPD settings. In addition to those, this example accepts: - CONFIG_EXAMPLE_THTTPD_NOMAC - (May be defined to use software assigned MAC) - CONFIG_EXAMPLE_THTTPD_DRIPADDR - Default router IP addess - CONFIG_EXAMPLE_THTTPD_NETMASK - Network mask + CONFIG_EXAMPLES_THTTPD_NOMAC - (May be defined to use software assigned MAC) + CONFIG_EXAMPLES_THTTPD_DRIPADDR - Default router IP addess + CONFIG_EXAMPLES_THTTPD_NETMASK - Network mask Applications using this example will need to provide an appconfig file in the configuration directory with instruction to build applications @@ -1335,11 +1335,11 @@ examples/uip This is a port of uIP tiny webserver example application. Settings specific to this example include: - CONFIG_EXAMPLE_UIP_NOMAC - (May be defined to use software assigned MAC) - CONFIG_EXAMPLE_UIP_IPADDR - Target IP address - CONFIG_EXAMPLE_UIP_DRIPADDR - Default router IP addess - CONFIG_EXAMPLE_UIP_NETMASK - Network mask - CONFIG_EXAMPLE_UIP_DHCPC - Select to get IP address via DHCP + CONFIG_EXAMPLES_UIP_NOMAC - (May be defined to use software assigned MAC) + CONFIG_EXAMPLES_UIP_IPADDR - Target IP address + CONFIG_EXAMPLES_UIP_DRIPADDR - Default router IP addess + CONFIG_EXAMPLES_UIP_NETMASK - Network mask + CONFIG_EXAMPLES_UIP_DHCPC - Select to get IP address via DHCP If you use DHCPC, then some special configuration network options are required. These include: @@ -1637,11 +1637,11 @@ examples/wget A simple web client example. It will obtain a file from a server using the HTTP protocol. Settings unique to this example include: - CONFIG_EXAMPLE_WGET_URL - The URL of the file to get - CONFIG_EXAMPLE_WGET_NOMAC - (May be defined to use software assigned MAC) - CONFIG_EXAMPLE_WGET_IPADDR - Target IP address - CONFIG_EXAMPLE_WGET_DRIPADDR - Default router IP addess - CONFIG_EXAMPLE_WGET_NETMASK - Network mask + CONFIG_EXAMPLES_WGET_URL - The URL of the file to get + CONFIG_EXAMPLES_WGET_NOMAC - (May be defined to use software assigned MAC) + CONFIG_EXAMPLES_WGET_IPADDR - Target IP address + CONFIG_EXAMPLES_WGET_DRIPADDR - Default router IP addess + CONFIG_EXAMPLES_WGET_NETMASK - Network mask This example uses netutils/webclient. Additional configuration settings apply to that code as follows (but built-in defaults are probably OK): diff --git a/apps/examples/adc/Kconfig b/apps/examples/adc/Kconfig index b6dca047c..85c875deb 100644 --- a/apps/examples/adc/Kconfig +++ b/apps/examples/adc/Kconfig @@ -6,8 +6,32 @@ config EXAMPLES_ADC bool "ADC example" default n + depends on ADC ---help--- Enable the ADC example if EXAMPLES_ADC + +config EXAMPLES_ADC_DEVPATH + string "ADC device path" + default "/dev/adc0" + ---help--- + The default path to the ADC device. Default: /dev/adc0 + +config EXAMPLES_ADC_NSAMPLES + int "Number of Sample Groups" + default 0 + depends on !NSH_BUILTIN_APPS + ---help--- + If NSH_BUILTIN_APPS is defined, then the number of samples is provided + on the command line and this value is ignored. Otherwise, this number + of samples is collected and the program terminates. Default: 0 (samples + are collected indefinitely). + +config EXAMPLES_ADC_GROUPSIZE + int "Number of Samples per Group" + default 4 + ---help--- + The number of samples to read at once. Default: 4 + endif diff --git a/apps/examples/adc/adc_main.c b/apps/examples/adc/adc_main.c index 4797265db..404fba8c1 100644 --- a/apps/examples/adc/adc_main.c +++ b/apps/examples/adc/adc_main.c @@ -57,6 +57,14 @@ * Pre-processor Definitions ****************************************************************************/ +/* Use CONFIG_EXAMPLES_ADC_NSAMPLES == 0 to mean to collect samples + * indefinitely. + */ + +#ifndef CONFIG_EXAMPLES_ADC_NSAMPLES +# define CONFIG_EXAMPLES_ADC_NSAMPLES 0 +#endif + /**************************************************************************** * Private Types ****************************************************************************/ @@ -249,7 +257,7 @@ int adc_main(int argc, char *argv[]) adc_devpath(&g_adcstate, CONFIG_EXAMPLES_ADC_DEVPATH); -#ifdef CONFIG_EXAMPLES_ADC_NSAMPLES +#if CONFIG_EXAMPLES_ADC_NSAMPLES > 0 g_adcstate.count = CONFIG_EXAMPLES_ADC_NSAMPLES; #else g_adcstate.count = 1; @@ -267,7 +275,7 @@ int adc_main(int argc, char *argv[]) * samples that we collect before returning. Otherwise, we never return */ -#if defined(CONFIG_NSH_BUILTIN_APPS) || defined(CONFIG_EXAMPLES_ADC_NSAMPLES) +#if defined(CONFIG_NSH_BUILTIN_APPS) || CONFIG_EXAMPLES_ADC_NSAMPLES > 0 message("adc_main: g_adcstate.count: %d\n", g_adcstate.count); #endif @@ -290,7 +298,7 @@ int adc_main(int argc, char *argv[]) #if defined(CONFIG_NSH_BUILTIN_APPS) for (; g_adcstate.count > 0; g_adcstate.count--) -#elif defined(CONFIG_EXAMPLES_ADC_NSAMPLES) +#elif CONFIG_EXAMPLES_ADC_NSAMPLES > 0 for (g_adcstate.count = 0; g_adcstate.count < CONFIG_EXAMPLES_ADC_NSAMPLES; g_adcstate.count++) #else for (;;) diff --git a/apps/examples/buttons/buttons_main.c b/apps/examples/buttons/buttons_main.c index a3f6449d4..5f25c1ef1 100644 --- a/apps/examples/buttons/buttons_main.c +++ b/apps/examples/buttons/buttons_main.c @@ -61,60 +61,60 @@ # error "CONFIG_ARCH_BUTTONS is not defined in the configuration" #endif -#ifndef CONFIG_EXAMPLE_BUTTONS_NAME0 -# define CONFIG_EXAMPLE_BUTTONS_NAME0 "BUTTON0" +#ifndef CONFIG_EXAMPLES_BUTTONS_NAME0 +# define CONFIG_EXAMPLES_BUTTONS_NAME0 "BUTTON0" #endif -#ifndef CONFIG_EXAMPLE_BUTTONS_NAME1 -# define CONFIG_EXAMPLE_BUTTONS_NAME1 "BUTTON1" +#ifndef CONFIG_EXAMPLES_BUTTONS_NAME1 +# define CONFIG_EXAMPLES_BUTTONS_NAME1 "BUTTON1" #endif -#ifndef CONFIG_EXAMPLE_BUTTONS_NAME2 -# define CONFIG_EXAMPLE_BUTTONS_NAME2 "BUTTON2" +#ifndef CONFIG_EXAMPLES_BUTTONS_NAME2 +# define CONFIG_EXAMPLES_BUTTONS_NAME2 "BUTTON2" #endif -#ifndef CONFIG_EXAMPLE_BUTTONS_NAME3 -# define CONFIG_EXAMPLE_BUTTONS_NAME3 "BUTTON3" +#ifndef CONFIG_EXAMPLES_BUTTONS_NAME3 +# define CONFIG_EXAMPLES_BUTTONS_NAME3 "BUTTON3" #endif -#ifndef CONFIG_EXAMPLE_BUTTONS_NAME4 -# define CONFIG_EXAMPLE_BUTTONS_NAME4 "BUTTON4" +#ifndef CONFIG_EXAMPLES_BUTTONS_NAME4 +# define CONFIG_EXAMPLES_BUTTONS_NAME4 "BUTTON4" #endif -#ifndef CONFIG_EXAMPLE_BUTTONS_NAME5 -# define CONFIG_EXAMPLE_BUTTONS_NAME5 "BUTTON5" +#ifndef CONFIG_EXAMPLES_BUTTONS_NAME5 +# define CONFIG_EXAMPLES_BUTTONS_NAME5 "BUTTON5" #endif -#ifndef CONFIG_EXAMPLE_BUTTONS_NAME6 -# define CONFIG_EXAMPLE_BUTTONS_NAME6 "BUTTON6" +#ifndef CONFIG_EXAMPLES_BUTTONS_NAME6 +# define CONFIG_EXAMPLES_BUTTONS_NAME6 "BUTTON6" #endif -#ifndef CONFIG_EXAMPLE_BUTTONS_NAME7 -# define CONFIG_EXAMPLE_BUTTONS_NAME7 "BUTTON7" +#ifndef CONFIG_EXAMPLES_BUTTONS_NAME7 +# define CONFIG_EXAMPLES_BUTTONS_NAME7 "BUTTON7" #endif #define BUTTON_MIN 0 #define BUTTON_MAX 7 -#ifndef CONFIG_EXAMPLE_BUTTONS_MIN -# define CONFIG_EXAMPLE_BUTTONS_MIN BUTTON_MIN +#ifndef CONFIG_EXAMPLES_BUTTONS_MIN +# define CONFIG_EXAMPLES_BUTTONS_MIN BUTTON_MIN #endif -#ifndef CONFIG_EXAMPLE_BUTTONS_MAX -# define CONFIG_EXAMPLE_BUTTONS_MAX BUTTON_MAX +#ifndef CONFIG_EXAMPLES_BUTTONS_MAX +# define CONFIG_EXAMPLES_BUTTONS_MAX BUTTON_MAX #endif -#if CONFIG_EXAMPLE_BUTTONS_MIN > CONFIG_EXAMPLE_BUTTONS_MAX -# error "CONFIG_EXAMPLE_BUTTONS_MIN > CONFIG_EXAMPLE_BUTTONS_MAX" +#if CONFIG_EXAMPLES_BUTTONS_MIN > CONFIG_EXAMPLES_BUTTONS_MAX +# error "CONFIG_EXAMPLES_BUTTONS_MIN > CONFIG_EXAMPLES_BUTTONS_MAX" #endif -#if CONFIG_EXAMPLE_BUTTONS_MAX > 7 -# error "CONFIG_EXAMPLE_BUTTONS_MAX > 7" +#if CONFIG_EXAMPLES_BUTTONS_MAX > 7 +# error "CONFIG_EXAMPLES_BUTTONS_MAX > 7" #endif -#ifndef CONFIG_EXAMPLE_IRQBUTTONS_MIN -# define CONFIG_EXAMPLE_IRQBUTTONS_MIN CONFIG_EXAMPLE_BUTTONS_MIN +#ifndef CONFIG_EXAMPLES_IRQBUTTONS_MIN +# define CONFIG_EXAMPLES_IRQBUTTONS_MIN CONFIG_EXAMPLES_BUTTONS_MIN #endif -#ifndef CONFIG_EXAMPLE_IRQBUTTONS_MAX -# define CONFIG_EXAMPLE_IRQBUTTONS_MAX CONFIG_EXAMPLE_BUTTONS_MAX +#ifndef CONFIG_EXAMPLES_IRQBUTTONS_MAX +# define CONFIG_EXAMPLES_IRQBUTTONS_MAX CONFIG_EXAMPLES_BUTTONS_MAX #endif -#if CONFIG_EXAMPLE_IRQBUTTONS_MIN > CONFIG_EXAMPLE_IRQBUTTONS_MAX -# error "CONFIG_EXAMPLE_IRQBUTTONS_MIN > CONFIG_EXAMPLE_IRQBUTTONS_MAX" +#if CONFIG_EXAMPLES_IRQBUTTONS_MIN > CONFIG_EXAMPLES_IRQBUTTONS_MAX +# error "CONFIG_EXAMPLES_IRQBUTTONS_MIN > CONFIG_EXAMPLES_IRQBUTTONS_MAX" #endif -#if CONFIG_EXAMPLE_IRQBUTTONS_MAX > 7 -# error "CONFIG_EXAMPLE_IRQBUTTONS_MAX > 7" +#if CONFIG_EXAMPLES_IRQBUTTONS_MAX > 7 +# error "CONFIG_EXAMPLES_IRQBUTTONS_MAX > 7" #endif #ifndef MIN @@ -124,8 +124,8 @@ # define MAX(a,b) (a > b ? a : b) #endif -#define MIN_BUTTON MIN(CONFIG_EXAMPLE_BUTTONS_MIN, CONFIG_EXAMPLE_IRQBUTTONS_MIN) -#define MAX_BUTTON MAX(CONFIG_EXAMPLE_BUTTONS_MAX, CONFIG_EXAMPLE_IRQBUTTONS_MAX) +#define MIN_BUTTON MIN(CONFIG_EXAMPLES_BUTTONS_MIN, CONFIG_EXAMPLES_IRQBUTTONS_MIN) +#define MAX_BUTTON MAX(CONFIG_EXAMPLES_BUTTONS_MAX, CONFIG_EXAMPLES_IRQBUTTONS_MAX) #define NUM_BUTTONS (MAX_BUTTON - MIN_BUTTON + 1) #define BUTTON_INDEX(b) ((b)-MIN_BUTTON) @@ -187,7 +187,7 @@ static const struct button_info_s g_buttoninfo[NUM_BUTTONS] = { #if MIN_BUTTON < 1 { - CONFIG_EXAMPLE_BUTTONS_NAME0, + CONFIG_EXAMPLES_BUTTONS_NAME0, #ifdef CONFIG_ARCH_IRQBUTTONS button0_handler #endif @@ -195,7 +195,7 @@ static const struct button_info_s g_buttoninfo[NUM_BUTTONS] = #endif #if MIN_BUTTON < 2 && MAX_BUTTON > 0 { - CONFIG_EXAMPLE_BUTTONS_NAME1, + CONFIG_EXAMPLES_BUTTONS_NAME1, #ifdef CONFIG_ARCH_IRQBUTTONS button1_handler #endif @@ -203,7 +203,7 @@ static const struct button_info_s g_buttoninfo[NUM_BUTTONS] = #endif #if MIN_BUTTON < 3 && MAX_BUTTON > 1 { - CONFIG_EXAMPLE_BUTTONS_NAME2, + CONFIG_EXAMPLES_BUTTONS_NAME2, #ifdef CONFIG_ARCH_IRQBUTTONS button2_handler #endif @@ -211,7 +211,7 @@ static const struct button_info_s g_buttoninfo[NUM_BUTTONS] = #endif #if MIN_BUTTON < 4 && MAX_BUTTON > 2 { - CONFIG_EXAMPLE_BUTTONS_NAME3, + CONFIG_EXAMPLES_BUTTONS_NAME3, #ifdef CONFIG_ARCH_IRQBUTTONS button3_handler #endif @@ -219,7 +219,7 @@ static const struct button_info_s g_buttoninfo[NUM_BUTTONS] = #endif #if MIN_BUTTON < 5 && MAX_BUTTON > 3 { - CONFIG_EXAMPLE_BUTTONS_NAME4, + CONFIG_EXAMPLES_BUTTONS_NAME4, #ifdef CONFIG_ARCH_IRQBUTTONS button4_handler #endif @@ -227,7 +227,7 @@ static const struct button_info_s g_buttoninfo[NUM_BUTTONS] = #endif #if MIN_BUTTON < 6 && MAX_BUTTON > 4 { - CONFIG_EXAMPLE_BUTTONS_NAME5, + CONFIG_EXAMPLES_BUTTONS_NAME5, #ifdef CONFIG_ARCH_IRQBUTTONS button5_handler #endif @@ -235,7 +235,7 @@ static const struct button_info_s g_buttoninfo[NUM_BUTTONS] = #endif #if MIN_BUTTON < 7 && MAX_BUTTON > 5 { - CONFIG_EXAMPLE_BUTTONS_NAME6, + CONFIG_EXAMPLES_BUTTONS_NAME6, #ifdef CONFIG_ARCH_IRQBUTTONS button6_handler #endif @@ -243,7 +243,7 @@ static const struct button_info_s g_buttoninfo[NUM_BUTTONS] = #endif #if MAX_BUTTON > 6 { - CONFIG_EXAMPLE_BUTTONS_NAME7, + CONFIG_EXAMPLES_BUTTONS_NAME7, #ifdef CONFIG_ARCH_IRQBUTTONS button7_handler #endif @@ -419,7 +419,7 @@ int buttons_main(int argc, char *argv[]) /* Register to recieve button interrupts */ #ifdef CONFIG_ARCH_IRQBUTTONS - for (i = CONFIG_EXAMPLE_IRQBUTTONS_MIN; i <= CONFIG_EXAMPLE_IRQBUTTONS_MAX; i++) + for (i = CONFIG_EXAMPLES_IRQBUTTONS_MIN; i <= CONFIG_EXAMPLES_IRQBUTTONS_MAX; i++) { xcpt_t oldhandler = up_irqbutton(i, g_buttoninfo[BUTTON_INDEX(i)].handler); @@ -488,7 +488,7 @@ int buttons_main(int argc, char *argv[]) /* Un-register button handlers */ #if defined(CONFIG_ARCH_IRQBUTTONS) && defined(CONFIG_NSH_BUILTIN_APPS) - for (i = CONFIG_EXAMPLE_IRQBUTTONS_MIN; i <= CONFIG_EXAMPLE_IRQBUTTONS_MAX; i++) + for (i = CONFIG_EXAMPLES_IRQBUTTONS_MIN; i <= CONFIG_EXAMPLES_IRQBUTTONS_MAX; i++) { (void)up_irqbutton(i, NULL); } diff --git a/apps/examples/dhcpd/target.c b/apps/examples/dhcpd/target.c index 9c554e8cd..37758d041 100644 --- a/apps/examples/dhcpd/target.c +++ b/apps/examples/dhcpd/target.c @@ -57,16 +57,16 @@ * but there are default values for those so we cannot check them here. */ -#ifndef CONFIG_EXAMPLE_DHCPD_IPADDR -# error "You must define CONFIG_EXAMPLE_DHCPD_IPADDR" +#ifndef CONFIG_EXAMPLES_DHCPD_IPADDR +# error "You must define CONFIG_EXAMPLES_DHCPD_IPADDR" #endif -#ifndef CONFIG_EXAMPLE_DHCPD_DRIPADDR -# error "You must define CONFIG_EXAMPLE_DHCPD_DRIPADDR" +#ifndef CONFIG_EXAMPLES_DHCPD_DRIPADDR +# error "You must define CONFIG_EXAMPLES_DHCPD_DRIPADDR" #endif -#ifndef CONFIG_EXAMPLE_DHCPD_NETMASK -# error "You must define CONFIG_EXAMPLE_DHCPD_NETMASK" +#ifndef CONFIG_EXAMPLES_DHCPD_NETMASK +# error "You must define CONFIG_EXAMPLES_DHCPD_NETMASK" #endif #ifndef CONFIG_NET @@ -92,13 +92,13 @@ int dhcpd_main(int argc, char *argv[]) { struct in_addr addr; -#if defined(CONFIG_EXAMPLE_DHCPD_NOMAC) +#if defined(CONFIG_EXAMPLES_DHCPD_NOMAC) uint8_t mac[IFHWADDRLEN]; #endif /* Many embedded network interfaces must have a software assigned MAC */ -#ifdef CONFIG_EXAMPLE_DHCPD_NOMAC +#ifdef CONFIG_EXAMPLES_DHCPD_NOMAC mac[0] = 0x00; mac[1] = 0xe0; mac[2] = 0xde; @@ -110,17 +110,17 @@ int dhcpd_main(int argc, char *argv[]) /* Set up our host address */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_DHCPD_IPADDR); + addr.s_addr = HTONL(CONFIG_EXAMPLES_DHCPD_IPADDR); uip_sethostaddr("eth0", &addr); /* Set up the default router address */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_DHCPD_DRIPADDR); + addr.s_addr = HTONL(CONFIG_EXAMPLES_DHCPD_DRIPADDR); uip_setdraddr("eth0", &addr); /* Setup the subnet mask */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_DHCPD_NETMASK); + addr.s_addr = HTONL(CONFIG_EXAMPLES_DHCPD_NETMASK); uip_setnetmask("eth0", &addr); /* Then start the server */ diff --git a/apps/examples/discover/Kconfig b/apps/examples/discover/Kconfig index 0a756d91d..1cbb7f120 100644 --- a/apps/examples/discover/Kconfig +++ b/apps/examples/discover/Kconfig @@ -3,7 +3,7 @@ # see misc/tools/kconfig-language.txt. # -config EXAMPLE_DISCOVER +config EXAMPLES_DISCOVER bool "UDP Discovery Example" default n depends on NET_UDP @@ -17,29 +17,29 @@ config EXAMPLE_DISCOVER It is also possible to address all classes with a kind of broadcast discover. -config EXAMPLE_DISCOVER_DHCPC +config EXAMPLES_DISCOVER_DHCPC bool "DHCP Client" default n - depends on EXAMPLE_DISCOVER && !NSH_BUILTIN_APPS + depends on EXAMPLES_DISCOVER && !NSH_BUILTIN_APPS select NETUTILS_DHCPC select NETUTILS_RESOLV -config EXAMPLE_DISCOVER_NOMAC +config EXAMPLES_DISCOVER_NOMAC bool "Use Canned MAC Address" default n - depends on EXAMPLE_DISCOVER && !NSH_BUILTIN_APPS + depends on EXAMPLES_DISCOVER && !NSH_BUILTIN_APPS -config EXAMPLE_DISCOVER_IPADDR +config EXAMPLES_DISCOVER_IPADDR hex "Target IP address" default 0x0a000002 - depends on EXAMPLE_DISCOVER && !NSH_BUILTIN_APPS && !EXAMPLE_DISCOVER_DHCPC + depends on EXAMPLES_DISCOVER && !NSH_BUILTIN_APPS && !EXAMPLES_DISCOVER_DHCPC -config EXAMPLE_DISCOVER_DRIPADDR +config EXAMPLES_DISCOVER_DRIPADDR hex "Default Router IP address (Gateway)" default 0x0a000001 - depends on EXAMPLE_DISCOVER && !NSH_BUILTIN_APPS + depends on EXAMPLES_DISCOVER && !NSH_BUILTIN_APPS -config EXAMPLE_DISCOVER_NETMASK +config EXAMPLES_DISCOVER_NETMASK hex "Network Mask" default 0xffffff00 - depends on EXAMPLE_DISCOVER && !NSH_BUILTIN_APPS + depends on EXAMPLES_DISCOVER && !NSH_BUILTIN_APPS diff --git a/apps/examples/discover/discover_main.c b/apps/examples/discover/discover_main.c index c3acb56df..259a93d98 100644 --- a/apps/examples/discover/discover_main.c +++ b/apps/examples/discover/discover_main.c @@ -54,7 +54,7 @@ #include #include -#ifdef CONFIG_EXAMPLE_DISCOVER_DHCPC +#ifdef CONFIG_EXAMPLES_DISCOVER_DHCPC # include #endif @@ -64,7 +64,7 @@ /* DHCPC may be used in conjunction with any other feature (or not) */ -#ifdef CONFIG_EXAMPLE_DISCOVER_DHCPC +#ifdef CONFIG_EXAMPLES_DISCOVER_DHCPC # include # include #endif @@ -93,16 +93,16 @@ int discover_main(int argc, char *argv[]) #ifndef CONFIG_NSH_BUILTIN_APPS struct in_addr addr; -#if defined(CONFIG_EXAMPLE_DISCOVER_DHCPC) || defined(CONFIG_EXAMPLE_DISCOVER_NOMAC) +#if defined(CONFIG_EXAMPLES_DISCOVER_DHCPC) || defined(CONFIG_EXAMPLES_DISCOVER_NOMAC) uint8_t mac[IFHWADDRLEN]; #endif -#ifdef CONFIG_EXAMPLE_DISCOVER_DHCPC +#ifdef CONFIG_EXAMPLES_DISCOVER_DHCPC void *handle; #endif /* Many embedded network interfaces must have a software assigned MAC */ -#ifdef CONFIG_EXAMPLE_DISCOVER_NOMAC +#ifdef CONFIG_EXAMPLES_DISCOVER_NOMAC mac[0] = 0x00; mac[1] = 0xe0; mac[2] = 0xde; @@ -114,24 +114,24 @@ int discover_main(int argc, char *argv[]) /* Set up our host address */ -#ifdef CONFIG_EXAMPLE_DISCOVER_DHCPC +#ifdef CONFIG_EXAMPLES_DISCOVER_DHCPC addr.s_addr = 0; #else - addr.s_addr = HTONL(CONFIG_EXAMPLE_DISCOVER_IPADDR); + addr.s_addr = HTONL(CONFIG_EXAMPLES_DISCOVER_IPADDR); #endif uip_sethostaddr("eth0", &addr); /* Set up the default router address */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_DISCOVER_DRIPADDR); + addr.s_addr = HTONL(CONFIG_EXAMPLES_DISCOVER_DRIPADDR); uip_setdraddr("eth0", &addr); /* Setup the subnet mask */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_DISCOVER_NETMASK); + addr.s_addr = HTONL(CONFIG_EXAMPLES_DISCOVER_NETMASK); uip_setnetmask("eth0", &addr); -#ifdef CONFIG_EXAMPLE_DISCOVER_DHCPC +#ifdef CONFIG_EXAMPLES_DISCOVER_DHCPC /* Set up the resolver */ resolv_init(); @@ -174,7 +174,7 @@ int discover_main(int argc, char *argv[]) printf("IP: %s\n", inet_ntoa(ds.ipaddr)); } -#endif /* CONFIG_EXAMPLE_DISCOVER_DHCPC */ +#endif /* CONFIG_EXAMPLES_DISCOVER_DHCPC */ #endif /* CONFIG_NSH_BUILTIN_APPS */ if (discover_start() < 0) diff --git a/apps/examples/ftpd/ftpd.h b/apps/examples/ftpd/ftpd.h index 6a439e818..ad20bdfb1 100644 --- a/apps/examples/ftpd/ftpd.h +++ b/apps/examples/ftpd/ftpd.h @@ -61,12 +61,12 @@ * If CONFIG_EXAMPLES_FTPD_NONETINIT is not defined, then the following may * be specified to customized the network configuration: * - * CONFIG_EXAMPLE_FTPD_NOMAC - If the hardware has no MAC address of its + * CONFIG_EXAMPLES_FTPD_NOMAC - If the hardware has no MAC address of its * own, define this =y to provide a bogus address for testing. - * CONFIG_EXAMPLE_FTPD_IPADDR - The target IP address. Default 10.0.0.2 - * CONFIG_EXAMPLE_FTPD_DRIPADDR - The default router address. Default + * CONFIG_EXAMPLES_FTPD_IPADDR - The target IP address. Default 10.0.0.2 + * CONFIG_EXAMPLES_FTPD_DRIPADDR - The default router address. Default * 10.0.0.1 - * CONFIG_EXAMPLE_FTPD_NETMASK - The network mask. Default: 255.255.255.0 + * CONFIG_EXAMPLES_FTPD_NETMASK - The network mask. Default: 255.255.255.0 */ #ifndef CONFIG_EXAMPLES_FTPD_PRIO @@ -92,18 +92,18 @@ #endif #ifdef CONFIG_EXAMPLES_FTPD_NONETINIT -# undef CONFIG_EXAMPLE_FTPD_IPADDR -# undef CONFIG_EXAMPLE_FTPD_DRIPADDR -# undef CONFIG_EXAMPLE_FTPD_NETMASK +# undef CONFIG_EXAMPLES_FTPD_IPADDR +# undef CONFIG_EXAMPLES_FTPD_DRIPADDR +# undef CONFIG_EXAMPLES_FTPD_NETMASK #else -# ifndef CONFIG_EXAMPLE_FTPD_IPADDR -# define CONFIG_EXAMPLE_FTPD_IPADDR 0x0a000002 +# ifndef CONFIG_EXAMPLES_FTPD_IPADDR +# define CONFIG_EXAMPLES_FTPD_IPADDR 0x0a000002 # endif -# ifndef CONFIG_EXAMPLE_FTPD_DRIPADDR -# define CONFIG_EXAMPLE_FTPD_DRIPADDR 0x0a000001 +# ifndef CONFIG_EXAMPLES_FTPD_DRIPADDR +# define CONFIG_EXAMPLES_FTPD_DRIPADDR 0x0a000001 # endif -# ifndef CONFIG_EXAMPLE_FTPD_NETMASK -# define CONFIG_EXAMPLE_FTPD_NETMASK 0xffffff00 +# ifndef CONFIG_EXAMPLES_FTPD_NETMASK +# define CONFIG_EXAMPLES_FTPD_NETMASK 0xffffff00 # endif #endif diff --git a/apps/examples/ftpd/ftpd_main.c b/apps/examples/ftpd/ftpd_main.c index 6d19f952c..1907da18c 100644 --- a/apps/examples/ftpd/ftpd_main.c +++ b/apps/examples/ftpd/ftpd_main.c @@ -83,13 +83,13 @@ static void fptd_netinit(void) { #ifndef CONFIG_EXAMPLES_FTPD_NONETINIT struct in_addr addr; -#ifdef CONFIG_EXAMPLE_FTPD_NOMAC +#ifdef CONFIG_EXAMPLES_FTPD_NOMAC uint8_t mac[IFHWADDRLEN]; #endif /* Many embedded network interfaces must have a software assigned MAC */ -#ifdef CONFIG_EXAMPLE_FTPD_NOMAC +#ifdef CONFIG_EXAMPLES_FTPD_NOMAC mac[0] = 0x00; mac[1] = 0xe0; mac[2] = 0xde; @@ -101,17 +101,17 @@ static void fptd_netinit(void) /* Set up our host address */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_FTPD_IPADDR); + addr.s_addr = HTONL(CONFIG_EXAMPLES_FTPD_IPADDR); uip_sethostaddr("eth0", &addr); /* Set up the default router address */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_FTPD_DRIPADDR); + addr.s_addr = HTONL(CONFIG_EXAMPLES_FTPD_DRIPADDR); uip_setdraddr("eth0", &addr); /* Setup the subnet mask */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_FTPD_NETMASK); + addr.s_addr = HTONL(CONFIG_EXAMPLES_FTPD_NETMASK); uip_setnetmask("eth0", &addr); #endif /* CONFIG_EXAMPLES_FTPD_NONETINIT */ } diff --git a/apps/examples/igmp/igmp.c b/apps/examples/igmp/igmp.c index 73ca8a3e6..ebb4feb07 100644 --- a/apps/examples/igmp/igmp.c +++ b/apps/examples/igmp/igmp.c @@ -64,8 +64,8 @@ * addresses=0xff (ff00::/8.) */ -#if ((CONFIG_EXAMPLE_IGMP_GRPADDR & 0xffff0000) < 0xe0000000ul) || \ - ((CONFIG_EXAMPLE_IGMP_GRPADDR & 0xffff0000) > 0xeffffffful) +#if ((CONFIG_EXAMPLES_IGMP_GRPADDR & 0xffff0000) < 0xe0000000ul) || \ + ((CONFIG_EXAMPLES_IGMP_GRPADDR & 0xffff0000) > 0xeffffffful) # error "Bad range for IGMP group address" #endif @@ -84,7 +84,7 @@ int igmp_main(int argc, char *argv[]) { struct in_addr addr; -#if defined(CONFIG_EXAMPLE_IGMP_NOMAC) +#if defined(CONFIG_EXAMPLES_IGMP_NOMAC) uint8_t mac[IFHWADDRLEN]; #endif @@ -92,7 +92,7 @@ int igmp_main(int argc, char *argv[]) /* Many embedded network interfaces must have a software assigned MAC */ -#ifdef CONFIG_EXAMPLE_IGMP_NOMAC +#ifdef CONFIG_EXAMPLES_IGMP_NOMAC mac[0] = 0x00; mac[1] = 0xe0; mac[2] = 0xde; @@ -104,24 +104,24 @@ int igmp_main(int argc, char *argv[]) /* Set up our host address */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_IGMP_IPADDR); + addr.s_addr = HTONL(CONFIG_EXAMPLES_IGMP_IPADDR); uip_sethostaddr("eth0", &addr); /* Set up the default router address */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_IGMP_DRIPADDR); + addr.s_addr = HTONL(CONFIG_EXAMPLES_IGMP_DRIPADDR); uip_setdraddr("eth0", &addr); /* Setup the subnet mask */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_IGMP_NETMASK); + addr.s_addr = HTONL(CONFIG_EXAMPLES_IGMP_NETMASK); uip_setnetmask("eth0", &addr); /* Not much of a test for now */ /* Join the group */ message("Join group...\n"); - addr.s_addr = HTONL(CONFIG_EXAMPLE_IGMP_GRPADDR); + addr.s_addr = HTONL(CONFIG_EXAMPLES_IGMP_GRPADDR); ipmsfilter("eth0", &addr, MCAST_INCLUDE); /* Wait a while */ diff --git a/apps/examples/nettest/Makefile b/apps/examples/nettest/Makefile index ac07665ab..9dd80e271 100644 --- a/apps/examples/nettest/Makefile +++ b/apps/examples/nettest/Makefile @@ -43,7 +43,7 @@ TARG_ASRCS = TARG_AOBJS = $(TARG_ASRCS:.S=$(OBJEXT)) TARG_CSRCS = nettest.c -ifeq ($(CONFIG_EXAMPLE_NETTEST_SERVER),y) +ifeq ($(CONFIG_EXAMPLES_NETTEST_SERVER),y) TARG_CSRCS += nettest_server.c else TARG_CSRCS += nettest_client.c @@ -61,19 +61,19 @@ else TARG_BIN = "$(TARG_POSIX)" endif -HOSTCFLAGS += -DCONFIG_EXAMPLE_NETTEST_HOST=1 -ifeq ($(CONFIG_EXAMPLE_NETTEST_SERVER),y) -HOSTCFLAGS += -DCONFIG_EXAMPLE_NETTEST_SERVER=1 \ - -DCONFIG_EXAMPLE_NETTEST_CLIENTIP="$(CONFIG_EXAMPLE_NETTEST_CLIENTIP)" +HOSTCFLAGS += -DCONFIG_EXAMPLES_NETTEST_HOST=1 +ifeq ($(CONFIG_EXAMPLES_NETTEST_SERVER),y) +HOSTCFLAGS += -DCONFIG_EXAMPLES_NETTEST_SERVER=1 \ + -DCONFIG_EXAMPLES_NETTEST_CLIENTIP="$(CONFIG_EXAMPLES_NETTEST_CLIENTIP)" endif -ifeq ($(CONFIG_EXAMPLE_NETTEST_PERFORMANCE),y) -HOSTCFLAGS += -DCONFIG_EXAMPLE_NETTEST_PERFORMANCE=1 +ifeq ($(CONFIG_EXAMPLES_NETTEST_PERFORMANCE),y) +HOSTCFLAGS += -DCONFIG_EXAMPLES_NETTEST_PERFORMANCE=1 endif HOST_SRCS = host.c -ifeq ($(CONFIG_EXAMPLE_NETTEST_SERVER),y) +ifeq ($(CONFIG_EXAMPLES_NETTEST_SERVER),y) HOST_SRCS += nettest_client.c else HOST_SRCS += nettest_server.c diff --git a/apps/examples/nettest/host.c b/apps/examples/nettest/host.c index 25cb85455..ad9d5e942 100644 --- a/apps/examples/nettest/host.c +++ b/apps/examples/nettest/host.c @@ -53,7 +53,7 @@ int main(int argc, char **argv, char **envp) { -#ifdef CONFIG_EXAMPLE_NETTEST_SERVER +#ifdef CONFIG_EXAMPLES_NETTEST_SERVER send_client(); #else recv_server(); diff --git a/apps/examples/nettest/nettest.c b/apps/examples/nettest/nettest.c index b95d9da62..81faf9b93 100644 --- a/apps/examples/nettest/nettest.c +++ b/apps/examples/nettest/nettest.c @@ -68,13 +68,13 @@ int nettest_main(int argc, char *argv[]) { struct in_addr addr; -#ifdef CONFIG_EXAMPLE_NETTEST_NOMAC +#ifdef CONFIG_EXAMPLES_NETTEST_NOMAC uint8_t mac[IFHWADDRLEN]; #endif /* Many embedded network interfaces must have a software assigned MAC */ -#ifdef CONFIG_EXAMPLE_NETTEST_NOMAC +#ifdef CONFIG_EXAMPLES_NETTEST_NOMAC mac[0] = 0x00; mac[1] = 0xe0; mac[2] = 0xde; @@ -86,20 +86,20 @@ int nettest_main(int argc, char *argv[]) /* Set up our host address */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_NETTEST_IPADDR); + addr.s_addr = HTONL(CONFIG_EXAMPLES_NETTEST_IPADDR); uip_sethostaddr("eth0", &addr); /* Set up the default router address */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_NETTEST_DRIPADDR); + addr.s_addr = HTONL(CONFIG_EXAMPLES_NETTEST_DRIPADDR); uip_setdraddr("eth0", &addr); /* Setup the subnet mask */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_NETTEST_NETMASK); + addr.s_addr = HTONL(CONFIG_EXAMPLES_NETTEST_NETMASK); uip_setnetmask("eth0", &addr); -#ifdef CONFIG_EXAMPLE_NETTEST_SERVER +#ifdef CONFIG_EXAMPLES_NETTEST_SERVER recv_server(); #else send_client(); diff --git a/apps/examples/nettest/nettest.h b/apps/examples/nettest/nettest.h index be33215cf..f05038584 100644 --- a/apps/examples/nettest/nettest.h +++ b/apps/examples/nettest/nettest.h @@ -40,7 +40,7 @@ * Included Files ****************************************************************************/ -#ifdef CONFIG_EXAMPLE_NETTEST_HOST +#ifdef CONFIG_EXAMPLES_NETTEST_HOST #else # include #endif @@ -49,7 +49,7 @@ * Definitions ****************************************************************************/ -#ifdef CONFIG_EXAMPLE_NETTEST_HOST +#ifdef CONFIG_EXAMPLES_NETTEST_HOST /* HTONS/L macros are unique to uIP */ # define HTONS(a) htons(a) diff --git a/apps/examples/nettest/nettest_client.c b/apps/examples/nettest/nettest_client.c index d498feb31..8ab5b14d6 100644 --- a/apps/examples/nettest/nettest_client.c +++ b/apps/examples/nettest/nettest_client.c @@ -56,12 +56,12 @@ void send_client(void) { struct sockaddr_in myaddr; char *outbuf; -#ifndef CONFIG_EXAMPLE_NETTEST_PERFORMANCE +#ifndef CONFIG_EXAMPLES_NETTEST_PERFORMANCE char *inbuf; #endif int sockfd; int nbytessent; -#ifndef CONFIG_EXAMPLE_NETTEST_PERFORMANCE +#ifndef CONFIG_EXAMPLES_NETTEST_PERFORMANCE int nbytesrecvd; int totalbytesrecvd; #endif @@ -71,7 +71,7 @@ void send_client(void) /* Allocate buffers */ outbuf = (char*)malloc(SENDSIZE); -#ifndef CONFIG_EXAMPLE_NETTEST_PERFORMANCE +#ifndef CONFIG_EXAMPLES_NETTEST_PERFORMANCE inbuf = (char*)malloc(SENDSIZE); if (!outbuf || !inbuf) #else @@ -98,7 +98,7 @@ void send_client(void) #if 0 myaddr.sin_addr.s_addr = HTONL(INADDR_LOOPBACK); #else - myaddr.sin_addr.s_addr = HTONL(CONFIG_EXAMPLE_NETTEST_CLIENTIP); + myaddr.sin_addr.s_addr = HTONL(CONFIG_EXAMPLES_NETTEST_CLIENTIP); #endif message("client: Connecting...\n"); @@ -121,7 +121,7 @@ void send_client(void) } } -#ifdef CONFIG_EXAMPLE_NETTEST_PERFORMANCE +#ifdef CONFIG_EXAMPLES_NETTEST_PERFORMANCE /* Then send messages forever */ for (;;) @@ -192,7 +192,7 @@ void send_client(void) close(sockfd); free(outbuf); -#ifndef CONFIG_EXAMPLE_NETTEST_PERFORMANCE +#ifndef CONFIG_EXAMPLES_NETTEST_PERFORMANCE free(inbuf); #endif return; @@ -203,7 +203,7 @@ errout_with_socket: errout_with_buffers: free(outbuf); -#ifndef CONFIG_EXAMPLE_NETTEST_PERFORMANCE +#ifndef CONFIG_EXAMPLES_NETTEST_PERFORMANCE free(inbuf); #endif exit(1); diff --git a/apps/examples/nettest/nettest_server.c b/apps/examples/nettest/nettest_server.c index 76a20e652..5757a778a 100644 --- a/apps/examples/nettest/nettest_server.c +++ b/apps/examples/nettest/nettest_server.c @@ -63,7 +63,7 @@ void recv_server(void) int acceptsd; socklen_t addrlen; int nbytesread; -#ifndef CONFIG_EXAMPLE_NETTEST_PERFORMANCE +#ifndef CONFIG_EXAMPLES_NETTEST_PERFORMANCE int totalbytesread; int nbytessent; int ch; @@ -143,7 +143,7 @@ void recv_server(void) } #endif -#ifdef CONFIG_EXAMPLE_NETTEST_PERFORMANCE +#ifdef CONFIG_EXAMPLES_NETTEST_PERFORMANCE /* Then receive data forever */ for (;;) diff --git a/apps/examples/poll/net_listener.c b/apps/examples/poll/net_listener.c index 81ad7cdcc..2be98673c 100644 --- a/apps/examples/poll/net_listener.c +++ b/apps/examples/poll/net_listener.c @@ -290,14 +290,14 @@ static inline bool net_mksocket(struct net_listener_s *nls) static void net_configure(void) { struct in_addr addr; -#if defined(CONFIG_EXAMPLE_POLL_NOMAC) +#if defined(CONFIG_EXAMPLES_POLL_NOMAC) uint8_t mac[IFHWADDRLEN]; #endif /* Configure uIP */ /* Many embedded network interfaces must have a software assigned MAC */ -#ifdef CONFIG_EXAMPLE_POLL_NOMAC +#ifdef CONFIG_EXAMPLES_POLL_NOMAC mac[0] = 0x00; mac[1] = 0xe0; mac[2] = 0xde; @@ -309,17 +309,17 @@ static void net_configure(void) /* Set up our host address */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_POLL_IPADDR); + addr.s_addr = HTONL(CONFIG_EXAMPLES_POLL_IPADDR); uip_sethostaddr("eth0", &addr); /* Set up the default router address */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_POLL_DRIPADDR); + addr.s_addr = HTONL(CONFIG_EXAMPLES_POLL_DRIPADDR); uip_setdraddr("eth0", &addr); /* Setup the subnet mask */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_POLL_NETMASK); + addr.s_addr = HTONL(CONFIG_EXAMPLES_POLL_NETMASK); uip_setnetmask("eth0", &addr); } diff --git a/apps/examples/poll/net_reader.c b/apps/examples/poll/net_reader.c index 8a13618c3..2f23bab3c 100644 --- a/apps/examples/poll/net_reader.c +++ b/apps/examples/poll/net_reader.c @@ -83,14 +83,14 @@ static void net_configure(void) { struct in_addr addr; -#if defined(CONFIG_EXAMPLE_POLL_NOMAC) +#if defined(CONFIG_EXAMPLES_POLL_NOMAC) uint8_t mac[IFHWADDRLEN]; #endif /* Configure uIP */ /* Many embedded network interfaces must have a software assigned MAC */ -#ifdef CONFIG_EXAMPLE_POLL_NOMAC +#ifdef CONFIG_EXAMPLES_POLL_NOMAC mac[0] = 0x00; mac[1] = 0xe0; mac[2] = 0xde; @@ -102,17 +102,17 @@ static void net_configure(void) /* Set up our host address */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_POLL_IPADDR); + addr.s_addr = HTONL(CONFIG_EXAMPLES_POLL_IPADDR); uip_sethostaddr("eth0", &addr); /* Set up the default router address */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_POLL_DRIPADDR); + addr.s_addr = HTONL(CONFIG_EXAMPLES_POLL_DRIPADDR); uip_setdraddr("eth0", &addr); /* Setup the subnet mask */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_POLL_NETMASK); + addr.s_addr = HTONL(CONFIG_EXAMPLES_POLL_NETMASK); uip_setnetmask("eth0", &addr); } diff --git a/apps/examples/sendmail/target.c b/apps/examples/sendmail/target.c index 8440c7813..59a51f5d9 100644 --- a/apps/examples/sendmail/target.c +++ b/apps/examples/sendmail/target.c @@ -52,32 +52,32 @@ * Pre-processor Defintitions ****************************************************************************/ -#ifndef CONFIG_EXAMPLE_SENDMAIL_RECIPIENT -# error "You must provice CONFIG_EXAMPLE_SENDMAIL_RECIPIENT" +#ifndef CONFIG_EXAMPLES_SENDMAIL_RECIPIENT +# error "You must provice CONFIG_EXAMPLES_SENDMAIL_RECIPIENT" #endif -#ifndef CONFIG_EXAMPLE_SENDMAIL_IPADDR -# error "You must provice CONFIG_EXAMPLE_SENDMAIL_IPADDR" +#ifndef CONFIG_EXAMPLES_SENDMAIL_IPADDR +# error "You must provice CONFIG_EXAMPLES_SENDMAIL_IPADDR" #endif -#ifndef CONFIG_EXAMPLE_SENDMAIL_DRIPADDR -# error "You must provice CONFIG_EXAMPLE_SENDMAIL_DRIPADDR" +#ifndef CONFIG_EXAMPLES_SENDMAIL_DRIPADDR +# error "You must provice CONFIG_EXAMPLES_SENDMAIL_DRIPADDR" #endif -#ifndef CONFIG_EXAMPLE_SENDMAIL_NETMASK -# error "You must provice CONFIG_EXAMPLE_SENDMAIL_NETMASK" +#ifndef CONFIG_EXAMPLES_SENDMAIL_NETMASK +# error "You must provice CONFIG_EXAMPLES_SENDMAIL_NETMASK" #endif -#ifndef CONFIG_EXAMPLE_SENDMAIL_SENDER -# define CONFIG_EXAMPLE_SENDMAIL_SENDER "nuttx-testing@example.com" +#ifndef CONFIG_EXAMPLES_SENDMAIL_SENDER +# define CONFIG_EXAMPLES_SENDMAIL_SENDER "nuttx-testing@example.com" #endif -#ifndef CONFIG_EXAMPLE_SENDMAIL_SUBJECT -# define CONFIG_EXAMPLE_SENDMAIL_SUBJECT "Testing SMTP from NuttX" +#ifndef CONFIG_EXAMPLES_SENDMAIL_SUBJECT +# define CONFIG_EXAMPLES_SENDMAIL_SUBJECT "Testing SMTP from NuttX" #endif -#ifndef CONFIG_EXAMPLE_SENDMAIL_BODY -# define CONFIG_EXAMPLE_SENDMAIL_BODY "Test message sent by NuttX" +#ifndef CONFIG_EXAMPLES_SENDMAIL_BODY +# define CONFIG_EXAMPLES_SENDMAIL_BODY "Test message sent by NuttX" #endif /**************************************************************************** @@ -85,10 +85,10 @@ ****************************************************************************/ static const char g_host_name[] = "localhost"; -static const char g_recipient[] = CONFIG_EXAMPLE_SENDMAIL_RECIPIENT; -static const char g_sender[] = CONFIG_EXAMPLE_SENDMAIL_SENDER; -static const char g_subject[] = CONFIG_EXAMPLE_SENDMAIL_SUBJECT; -static const char g_msg_body[] = CONFIG_EXAMPLE_SENDMAIL_BODY "\r\n"; +static const char g_recipient[] = CONFIG_EXAMPLES_SENDMAIL_RECIPIENT; +static const char g_sender[] = CONFIG_EXAMPLES_SENDMAIL_SENDER; +static const char g_subject[] = CONFIG_EXAMPLES_SENDMAIL_SUBJECT; +static const char g_msg_body[] = CONFIG_EXAMPLES_SENDMAIL_BODY "\r\n"; /**************************************************************************** * Private Functions @@ -105,7 +105,7 @@ static const char g_msg_body[] = CONFIG_EXAMPLE_SENDMAIL_BODY "\r\n"; int sendmail_main(int argc, char *argv[]) { struct in_addr addr; -#if defined(CONFIG_EXAMPLE_SENDMAIL_NOMAC) +#if defined(CONFIG_EXAMPLES_SENDMAIL_NOMAC) uint8_t mac[IFHWADDRLEN]; #endif void *handle; @@ -117,7 +117,7 @@ int sendmail_main(int argc, char *argv[]) /* Many embedded network interfaces must have a software assigned MAC */ -#ifdef CONFIG_EXAMPLE_SENDMAIL_NOMAC +#ifdef CONFIG_EXAMPLES_SENDMAIL_NOMAC mac[0] = 0x00; mac[1] = 0xe0; mac[2] = 0xde; @@ -129,17 +129,17 @@ int sendmail_main(int argc, char *argv[]) /* Set up our host address */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_SENDMAIL_IPADDR); + addr.s_addr = HTONL(CONFIG_EXAMPLES_SENDMAIL_IPADDR); uip_sethostaddr("eth0", &addr); /* Set up the default router address */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_SENDMAIL_DRIPADDR); + addr.s_addr = HTONL(CONFIG_EXAMPLES_SENDMAIL_DRIPADDR); uip_setdraddr("eth0", &addr); /* Setup the subnet mask */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_SENDMAIL_NETMASK); + addr.s_addr = HTONL(CONFIG_EXAMPLES_SENDMAIL_NETMASK); uip_setnetmask("eth0", &addr); /* Then send the mail */ diff --git a/apps/examples/telnetd/shell.c b/apps/examples/telnetd/shell.c index 3033698c5..3058daa39 100644 --- a/apps/examples/telnetd/shell.c +++ b/apps/examples/telnetd/shell.c @@ -186,13 +186,13 @@ int shell_session(int argc, char *argv[]) static void shell_netinit(void) { struct in_addr addr; -#ifdef CONFIG_EXAMPLE_TELNETD_NOMAC +#ifdef CONFIG_EXAMPLES_TELNETD_NOMAC uint8_t mac[IFHWADDRLEN]; #endif /* Many embedded network interfaces must have a software assigned MAC */ -#ifdef CONFIG_EXAMPLE_TELNETD_NOMAC +#ifdef CONFIG_EXAMPLES_TELNETD_NOMAC mac[0] = 0x00; mac[1] = 0xe0; mac[2] = 0xde; @@ -204,17 +204,17 @@ static void shell_netinit(void) /* Set up our host address */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_TELNETD_IPADDR); + addr.s_addr = HTONL(CONFIG_EXAMPLES_TELNETD_IPADDR); uip_sethostaddr("eth0", &addr); /* Set up the default router address */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_TELNETD_DRIPADDR); + addr.s_addr = HTONL(CONFIG_EXAMPLES_TELNETD_DRIPADDR); uip_setdraddr("eth0", &addr); /* Setup the subnet mask */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_TELNETD_NETMASK); + addr.s_addr = HTONL(CONFIG_EXAMPLES_TELNETD_NETMASK); uip_setnetmask("eth0", &addr); } diff --git a/apps/examples/telnetd/shell.h b/apps/examples/telnetd/shell.h index a5cec32b3..59d51a562 100644 --- a/apps/examples/telnetd/shell.h +++ b/apps/examples/telnetd/shell.h @@ -47,12 +47,12 @@ * Default: SCHED_PRIORITY_DEFAULT * CONFIG_EXAMPLES_TELNETD_CLIENTSTACKSIZE - Stack size allocated for the * Telnet client. Default: 2048 - * CONFIG_EXAMPLE_TELNETD_NOMAC - If the hardware has no MAC address of its + * CONFIG_EXAMPLES_TELNETD_NOMAC - If the hardware has no MAC address of its * own, define this =y to provide a bogus address for testing. - * CONFIG_EXAMPLE_TELNETD_IPADDR - The target IP address. Default 10.0.0.2 - * CONFIG_EXAMPLE_TELNETD_DRIPADDR - The default router address. Default + * CONFIG_EXAMPLES_TELNETD_IPADDR - The target IP address. Default 10.0.0.2 + * CONFIG_EXAMPLES_TELNETD_DRIPADDR - The default router address. Default * 10.0.0.1 - * CONFIG_EXAMPLE_TELNETD_NETMASK - The network mask. Default: 255.255.255.0 + * CONFIG_EXAMPLES_TELNETD_NETMASK - The network mask. Default: 255.255.255.0 */ #ifndef CONFIG_EXAMPLES_TELNETD_DAEMONPRIO @@ -71,14 +71,14 @@ # define CONFIG_EXAMPLES_TELNETD_CLIENTSTACKSIZE 2048 #endif -#ifndef CONFIG_EXAMPLE_TELNETD_IPADDR -# define CONFIG_EXAMPLE_TELNETD_IPADDR 0x0a000002 +#ifndef CONFIG_EXAMPLES_TELNETD_IPADDR +# define CONFIG_EXAMPLES_TELNETD_IPADDR 0x0a000002 #endif -#ifndef CONFIG_EXAMPLE_TELNETD_DRIPADDR -# define CONFIG_EXAMPLE_TELNETD_DRIPADDR 0x0a000002 +#ifndef CONFIG_EXAMPLES_TELNETD_DRIPADDR +# define CONFIG_EXAMPLES_TELNETD_DRIPADDR 0x0a000002 #endif -#ifndef CONFIG_EXAMPLE_TELNETD_NETMASK -# define CONFIG_EXAMPLE_TELNETD_NETMASK 0xffffff00 +#ifndef CONFIG_EXAMPLES_TELNETD_NETMASK +# define CONFIG_EXAMPLES_TELNETD_NETMASK 0xffffff00 #endif /* Other definitions ********************************************************/ diff --git a/apps/examples/thttpd/thttpd_main.c b/apps/examples/thttpd/thttpd_main.c index f4d5d58db..b31d0a864 100644 --- a/apps/examples/thttpd/thttpd_main.c +++ b/apps/examples/thttpd/thttpd_main.c @@ -99,7 +99,7 @@ /* No MAC address operations */ -# undef CONFIG_EXAMPLE_THTTPD_NOMAC +# undef CONFIG_EXAMPLES_THTTPD_NOMAC /* TTY device to use */ @@ -172,7 +172,7 @@ int g_thttpdnsymbols; int thttp_main(int argc, char *argv[]) { struct in_addr addr; -#ifdef CONFIG_EXAMPLE_THTTPD_NOMAC +#ifdef CONFIG_EXAMPLES_THTTPD_NOMAC uint8_t mac[IFHWADDRLEN]; #endif char *thttpd_argv = "thttpd"; @@ -191,7 +191,7 @@ int thttp_main(int argc, char *argv[]) /* Many embedded network interfaces must have a software assigned MAC */ -#ifdef CONFIG_EXAMPLE_THTTPD_NOMAC +#ifdef CONFIG_EXAMPLES_THTTPD_NOMAC message("Assigning MAC\n"); mac[0] = 0x00; @@ -211,12 +211,12 @@ int thttp_main(int argc, char *argv[]) /* Set up the default router address */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_THTTPD_DRIPADDR); + addr.s_addr = HTONL(CONFIG_EXAMPLES_THTTPD_DRIPADDR); uip_setdraddr(NET_DEVNAME, &addr); /* Setup the subnet mask */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_THTTPD_NETMASK); + addr.s_addr = HTONL(CONFIG_EXAMPLES_THTTPD_NETMASK); uip_setnetmask(NET_DEVNAME, &addr); /* Initialize the NXFLAT binary loader */ diff --git a/apps/examples/udp/Makefile b/apps/examples/udp/Makefile index 337d323e8..17438321c 100644 --- a/apps/examples/udp/Makefile +++ b/apps/examples/udp/Makefile @@ -42,7 +42,7 @@ include $(APPDIR)/Make.defs TARG_ASRCS = TARG_CSRCS = target.c -ifeq ($(CONFIG_EXAMPLE_UDP_SERVER),y) +ifeq ($(CONFIG_EXAMPLES_UDP_SERVER),y) TARG_CSRCS += udp-server.c else TARG_CSRCS += udp-client.c @@ -60,14 +60,14 @@ else TARG_BIN = "$(APPDIR)/libapps$(LIBEXT)" endif -HOSTCFLAGS += -DCONFIG_EXAMPLE_UDP_HOST=1 -ifeq ($(CONFIG_EXAMPLE_UDP_SERVER),y) -HOSTCFLAGS += -DCONFIG_EXAMPLE_UDP_SERVER=1 \ - -DCONFIG_EXAMPLE_UDP_SERVERIP="$(CONFIG_EXAMPLE_UDP_SERVERIP)" +HOSTCFLAGS += -DCONFIG_EXAMPLES_UDP_HOST=1 +ifeq ($(CONFIG_EXAMPLES_UDP_SERVER),y) +HOSTCFLAGS += -DCONFIG_EXAMPLES_UDP_SERVER=1 \ + -DCONFIG_EXAMPLES_UDP_SERVERIP="$(CONFIG_EXAMPLES_UDP_SERVERIP)" endif HOST_SRCS = host.c -ifeq ($(CONFIG_EXAMPLE_UDP_SERVER),y) +ifeq ($(CONFIG_EXAMPLES_UDP_SERVER),y) HOST_SRCS += udp-client.c else HOST_SRCS += udp-server.c diff --git a/apps/examples/udp/host.c b/apps/examples/udp/host.c index 9d2aa73d9..e103acd8c 100644 --- a/apps/examples/udp/host.c +++ b/apps/examples/udp/host.c @@ -53,7 +53,7 @@ int main(int argc, char **argv, char **envp) { -#ifdef CONFIG_EXAMPLE_UDP_SERVER +#ifdef CONFIG_EXAMPLES_UDP_SERVER send_client(); #else recv_server(); diff --git a/apps/examples/udp/target.c b/apps/examples/udp/target.c index e43ff2a0b..d7b64638d 100644 --- a/apps/examples/udp/target.c +++ b/apps/examples/udp/target.c @@ -68,20 +68,20 @@ int udp_main(int argc, char *argv[]) /* Set up our host address */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_UDP_IPADDR); + addr.s_addr = HTONL(CONFIG_EXAMPLES_UDP_IPADDR); uip_sethostaddr("eth0", &addr); /* Set up the default router address */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_UDP_DRIPADDR); + addr.s_addr = HTONL(CONFIG_EXAMPLES_UDP_DRIPADDR); uip_setdraddr("eth0", &addr); /* Setup the subnet mask */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_UDP_NETMASK); + addr.s_addr = HTONL(CONFIG_EXAMPLES_UDP_NETMASK); uip_setnetmask("eth0", &addr); -#ifdef CONFIG_EXAMPLE_UDP_SERVER +#ifdef CONFIG_EXAMPLES_UDP_SERVER recv_server(); #else send_client(); diff --git a/apps/examples/udp/udp-client.c b/apps/examples/udp/udp-client.c index fb98ab342..6b8473582 100644 --- a/apps/examples/udp/udp-client.c +++ b/apps/examples/udp/udp-client.c @@ -102,7 +102,7 @@ void send_client(void) server.sin_family = AF_INET; server.sin_port = HTONS(PORTNO); - server.sin_addr.s_addr = HTONL(CONFIG_EXAMPLE_UDP_SERVERIP); + server.sin_addr.s_addr = HTONL(CONFIG_EXAMPLES_UDP_SERVERIP); message("client: %d. Sending %d bytes\n", offset, SENDSIZE); nbytes = sendto(sockfd, outbuf, SENDSIZE, 0, diff --git a/apps/examples/udp/udp-internal.h b/apps/examples/udp/udp-internal.h index 04a685d17..2a966c746 100644 --- a/apps/examples/udp/udp-internal.h +++ b/apps/examples/udp/udp-internal.h @@ -40,7 +40,7 @@ * Included Files ****************************************************************************/ -#ifdef CONFIG_EXAMPLE_UDP_HOST +#ifdef CONFIG_EXAMPLES_UDP_HOST #else # include #endif @@ -49,7 +49,7 @@ * Definitions ****************************************************************************/ -#ifdef CONFIG_EXAMPLE_UDP_HOST +#ifdef CONFIG_EXAMPLES_UDP_HOST /* HTONS/L macros are unique to uIP */ # define HTONS(a) htons(a) diff --git a/apps/examples/uip/uip_main.c b/apps/examples/uip/uip_main.c index b552aed75..6c2f96f39 100644 --- a/apps/examples/uip/uip_main.c +++ b/apps/examples/uip/uip_main.c @@ -59,7 +59,7 @@ #include -#ifdef CONFIG_EXAMPLE_UIP_DHCPC +#ifdef CONFIG_EXAMPLES_UIP_DHCPC #include #endif @@ -69,7 +69,7 @@ /* DHCPC may be used in conjunction with any other feature (or not) */ -#ifdef CONFIG_EXAMPLE_UIP_DHCPC +#ifdef CONFIG_EXAMPLES_UIP_DHCPC # include # include #endif @@ -113,16 +113,16 @@ int uip_main(int argc, char *argv[]) { struct in_addr addr; -#if defined(CONFIG_EXAMPLE_UIP_DHCPC) || defined(CONFIG_EXAMPLE_UIP_NOMAC) +#if defined(CONFIG_EXAMPLES_UIP_DHCPC) || defined(CONFIG_EXAMPLES_UIP_NOMAC) uint8_t mac[IFHWADDRLEN]; #endif -#ifdef CONFIG_EXAMPLE_UIP_DHCPC +#ifdef CONFIG_EXAMPLES_UIP_DHCPC void *handle; #endif /* Many embedded network interfaces must have a software assigned MAC */ -#ifdef CONFIG_EXAMPLE_UIP_NOMAC +#ifdef CONFIG_EXAMPLES_UIP_NOMAC mac[0] = 0x00; mac[1] = 0xe0; mac[2] = 0xde; @@ -134,24 +134,24 @@ int uip_main(int argc, char *argv[]) /* Set up our host address */ -#ifdef CONFIG_EXAMPLE_UIP_DHCPC +#ifdef CONFIG_EXAMPLES_UIP_DHCPC addr.s_addr = 0; #else - addr.s_addr = HTONL(CONFIG_EXAMPLE_UIP_IPADDR); + addr.s_addr = HTONL(CONFIG_EXAMPLES_UIP_IPADDR); #endif uip_sethostaddr("eth0", &addr); /* Set up the default router address */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_UIP_DRIPADDR); + addr.s_addr = HTONL(CONFIG_EXAMPLES_UIP_DRIPADDR); uip_setdraddr("eth0", &addr); /* Setup the subnet mask */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_UIP_NETMASK); + addr.s_addr = HTONL(CONFIG_EXAMPLES_UIP_NETMASK); uip_setnetmask("eth0", &addr); -#ifdef CONFIG_EXAMPLE_UIP_DHCPC +#ifdef CONFIG_EXAMPLES_UIP_DHCPC /* Set up the resolver */ resolv_init(); diff --git a/apps/examples/wget/Kconfig b/apps/examples/wget/Kconfig index f7a1927f3..f7d5a2a89 100644 --- a/apps/examples/wget/Kconfig +++ b/apps/examples/wget/Kconfig @@ -6,8 +6,32 @@ config EXAMPLES_WGET bool "wget example" default n + depends on NET_TCP && !NSH_BUILTIN_APPS ---help--- Enable the wget example if EXAMPLES_WGET + +config EXAMPLES_WGET_URL + string "File URL" + default "" + ---help--- + The URL of the file to get + +config EXAMPLES_WGET_NOMAC + bool "Use Canned MAC Address" + default n + +config EXAMPLES_WGET_IPADDR + hex "Target IP address" + default 0x0a000002 + +config EXAMPLES_WGET_DRIPADDR + hex "Default Router IP address (Gateway)" + default 0x0a000001 + +config EXAMPLES_WGET_NETMASK + hex "Network Mask" + default 0xffffff00 + endif diff --git a/apps/examples/wget/target.c b/apps/examples/wget/target.c index 5c5c65665..d205a81ae 100644 --- a/apps/examples/wget/target.c +++ b/apps/examples/wget/target.c @@ -62,16 +62,16 @@ * but there are default values for those so we cannot check them here. */ -#ifndef CONFIG_EXAMPLE_WGET_IPADDR -# error "You must define CONFIG_EXAMPLE_WGET_IPADDR" +#ifndef CONFIG_EXAMPLES_WGET_IPADDR +# error "You must define CONFIG_EXAMPLES_WGET_IPADDR" #endif -#ifndef CONFIG_EXAMPLE_WGET_DRIPADDR -# error "You must define CONFIG_EXAMPLE_WGET_DRIPADDR" +#ifndef CONFIG_EXAMPLES_WGET_DRIPADDR +# error "You must define CONFIG_EXAMPLES_WGET_DRIPADDR" #endif -#ifndef CONFIG_EXAMPLE_WGET_NETMASK -# error "You must define CONFIG_EXAMPLE_WGET_NETMASK" +#ifndef CONFIG_EXAMPLES_WGET_NETMASK +# error "You must define CONFIG_EXAMPLES_WGET_NETMASK" #endif #ifndef CONFIG_NET @@ -112,13 +112,13 @@ static void callback(FAR char **buffer, int offset, int datend, int wget_main(int argc, char *argv[]) { struct in_addr addr; -#if defined(CONFIG_EXAMPLE_WGET_NOMAC) +#if defined(CONFIG_EXAMPLES_WGET_NOMAC) uint8_t mac[IFHWADDRLEN]; #endif /* Many embedded network interfaces must have a software assigned MAC */ -#ifdef CONFIG_EXAMPLE_WGET_NOMAC +#ifdef CONFIG_EXAMPLES_WGET_NOMAC mac[0] = 0x00; mac[1] = 0xe0; mac[2] = 0xde; @@ -130,21 +130,21 @@ int wget_main(int argc, char *argv[]) /* Set up our host address */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_WGET_IPADDR); + addr.s_addr = HTONL(CONFIG_EXAMPLES_WGET_IPADDR); uip_sethostaddr("eth0", &addr); /* Set up the default router address */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_WGET_DRIPADDR); + addr.s_addr = HTONL(CONFIG_EXAMPLES_WGET_DRIPADDR); uip_setdraddr("eth0", &addr); /* Setup the subnet mask */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_WGET_NETMASK); + addr.s_addr = HTONL(CONFIG_EXAMPLES_WGET_NETMASK); uip_setnetmask("eth0", &addr); /* Then start the server */ - wget(CONFIG_EXAMPLE_WGET_URL, g_iobuffer, 512, callback, NULL); + wget(CONFIG_EXAMPLES_WGET_URL, g_iobuffer, 512, callback, NULL); return 0; } diff --git a/apps/examples/wlan/wlan_main.c b/apps/examples/wlan/wlan_main.c index dcb8c770a..aa48a0238 100644 --- a/apps/examples/wlan/wlan_main.c +++ b/apps/examples/wlan/wlan_main.c @@ -64,7 +64,7 @@ /* DHCPC may be used in conjunction with any other feature (or not) */ -#ifdef CONFIG_EXAMPLE_WLAN_DHCPC +#ifdef CONFIG_EXAMPLES_WLAN_DHCPC # include # include # include @@ -131,11 +131,11 @@ static struct usbhost_driver_s *g_drvr; static inline void wlan_bringup(void) { -#if defined(CONFIG_EXAMPLE_WLAN_DHCPC) || defined(CONFIG_EXAMPLE_WLAN_NOMAC) +#if defined(CONFIG_EXAMPLES_WLAN_DHCPC) || defined(CONFIG_EXAMPLES_WLAN_NOMAC) uint8_t mac[IFHWADDRLEN]; #endif struct in_addr addr; -#ifdef CONFIG_EXAMPLE_WLAN_DHCPC +#ifdef CONFIG_EXAMPLES_WLAN_DHCPC void *handle; #endif @@ -143,7 +143,7 @@ static inline void wlan_bringup(void) * MAC */ -#ifdef CONFIG_EXAMPLE_WLAN_NOMAC +#ifdef CONFIG_EXAMPLES_WLAN_NOMAC mac[0] = 0x00; mac[1] = 0xe0; mac[2] = 0xde; @@ -155,24 +155,24 @@ static inline void wlan_bringup(void) /* Set up the default router address */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_WLAN_DRIPADDR); + addr.s_addr = HTONL(CONFIG_EXAMPLES_WLAN_DRIPADDR); uip_setdraddr("eth0", &addr); /* Setup the subnet mask */ - addr.s_addr = HTONL(CONFIG_EXAMPLE_WLAN_NETMASK); + addr.s_addr = HTONL(CONFIG_EXAMPLES_WLAN_NETMASK); uip_setnetmask("eth0", &addr); /* Set up our host address */ -#ifdef CONFIG_EXAMPLE_WLAN_DHCPC +#ifdef CONFIG_EXAMPLES_WLAN_DHCPC addr.s_addr = 0; #else - addr.s_addr = HTONL(CONFIG_EXAMPLE_WLAN_IPADDR); + addr.s_addr = HTONL(CONFIG_EXAMPLES_WLAN_IPADDR); #endif uip_sethostaddr("eth0", &addr); -#ifdef CONFIG_EXAMPLE_WLAN_DHCPC +#ifdef CONFIG_EXAMPLES_WLAN_DHCPC /* Set up the resolver */ resolv_init(); diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 4ea03f34f..eb85a8e7c 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3461,3 +3461,5 @@ * board.h file for shenzhou, fire-stm32v2, and olimex-stm32-p107: Add frequencies for HSE, HSI, LSE, and LSI. These are needed by the STM32 watchdog driver. + * CONFIG_EXAMPLES_*: To make things consistent, changed all occurrences + of CONFIG_EXAMPLE_* to CONFIG_EXAMPLES_*. diff --git a/nuttx/Documentation/NuttXRelated.html b/nuttx/Documentation/NuttXRelated.html index bc55bbfc1..978eb1d44 100644 --- a/nuttx/Documentation/NuttXRelated.html +++ b/nuttx/Documentation/NuttXRelated.html @@ -41,6 +41,7 @@
  • Osmocom-BB
  • PX4 Autopilot
  • RGMP
  • +
  • Top Multi-Rotor (TMR)
  • diff --git a/nuttx/arch/sim/src/up_tapdev.c b/nuttx/arch/sim/src/up_tapdev.c index d0deea6d9..f2bbcc14a 100644 --- a/nuttx/arch/sim/src/up_tapdev.c +++ b/nuttx/arch/sim/src/up_tapdev.c @@ -72,7 +72,7 @@ extern int uipdriver_setmacaddr(unsigned char *macaddr); #define DEVTAP "/dev/net/tun" -#ifndef CONFIG_EXAMPLE_UIP_DHCPC +#ifndef CONFIG_EXAMPLES_UIP_DHCPC # define UIP_IPADDR0 192 # define UIP_IPADDR1 168 # define UIP_IPADDR2 0 diff --git a/nuttx/arch/sim/src/up_wpcap.c b/nuttx/arch/sim/src/up_wpcap.c index 42e8764f8..62f0b6ad0 100644 --- a/nuttx/arch/sim/src/up_wpcap.c +++ b/nuttx/arch/sim/src/up_wpcap.c @@ -62,7 +62,7 @@ extern int uipdriver_setmacaddr(unsigned char *macaddr); #define BUF ((struct uip_eth_hdr *)&uip_buf[0]) -#ifndef CONFIG_EXAMPLE_UIP_DHCPC +#ifndef CONFIG_EXAMPLES_UIP_DHCPC # define UIP_IPADDR (10 << 24 | 0 << 16 | 0 << 8 | 1) #else # define UIP_IPADDR (0) diff --git a/nuttx/configs/amber/hello/defconfig b/nuttx/configs/amber/hello/defconfig index 66127604e..fece8db36 100644 --- a/nuttx/configs/amber/hello/defconfig +++ b/nuttx/configs/amber/hello/defconfig @@ -318,21 +318,21 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/avr32dev1/nsh/defconfig b/nuttx/configs/avr32dev1/nsh/defconfig index b9f6e35a6..7e75380c0 100755 --- a/nuttx/configs/avr32dev1/nsh/defconfig +++ b/nuttx/configs/avr32dev1/nsh/defconfig @@ -341,20 +341,20 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/avr32dev1/ostest/defconfig b/nuttx/configs/avr32dev1/ostest/defconfig index 74ac8f072..b70cbb6af 100755 --- a/nuttx/configs/avr32dev1/ostest/defconfig +++ b/nuttx/configs/avr32dev1/ostest/defconfig @@ -341,20 +341,20 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/c5471evm/httpd/defconfig b/nuttx/configs/c5471evm/httpd/defconfig index 1e599d9a1..372fb330f 100644 --- a/nuttx/configs/c5471evm/httpd/defconfig +++ b/nuttx/configs/c5471evm/httpd/defconfig @@ -210,21 +210,21 @@ CONFIG_NET_RESOLV_ENTRIES=4 # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_NOMAC=y -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=y +CONFIG_EXAMPLES_UIP_NOMAC=y +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=y # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/nsh @@ -241,11 +241,11 @@ CONFIG_NSH_NETMASK=0xffffff00 # # Settings for examples/wget # -CONFIG_EXAMPLE_WGET_URL="http://www.nuttx.org/index.html" -CONFIG_EXAMPLE_WGET_NOMAC=y -CONFIG_EXAMPLE_WGET_IPADDR=0x0a000002 -CONFIG_EXAMPLE_WGET_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_WGET_NETMASK=0xffffff00 +CONFIG_EXAMPLES_WGET_URL="http://www.nuttx.org/index.html" +CONFIG_EXAMPLES_WGET_NOMAC=y +CONFIG_EXAMPLES_WGET_IPADDR=0x0a000002 +CONFIG_EXAMPLES_WGET_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_WGET_NETMASK=0xffffff00 # # Stack and heap information diff --git a/nuttx/configs/c5471evm/nettest/defconfig b/nuttx/configs/c5471evm/nettest/defconfig index 807a23f15..179b4c185 100644 --- a/nuttx/configs/c5471evm/nettest/defconfig +++ b/nuttx/configs/c5471evm/nettest/defconfig @@ -210,21 +210,21 @@ CONFIG_NET_RESOLV_ENTRIES=4 # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_NOMAC=y -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_NOMAC=y +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/nsh @@ -241,11 +241,11 @@ CONFIG_NSH_NETMASK=0xffffff00 # # Settings for examples/wget # -CONFIG_EXAMPLE_WGET_URL="http://www.nuttx.org/index.html" -CONFIG_EXAMPLE_WGET_NOMAC=y -CONFIG_EXAMPLE_WGET_IPADDR=0x0a000002 -CONFIG_EXAMPLE_WGET_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_WGET_NETMASK=0xffffff00 +CONFIG_EXAMPLES_WGET_URL="http://www.nuttx.org/index.html" +CONFIG_EXAMPLES_WGET_NOMAC=y +CONFIG_EXAMPLES_WGET_IPADDR=0x0a000002 +CONFIG_EXAMPLES_WGET_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_WGET_NETMASK=0xffffff00 # # Stack and heap information diff --git a/nuttx/configs/c5471evm/nsh/defconfig b/nuttx/configs/c5471evm/nsh/defconfig index 9f5bc6373..5746f833a 100644 --- a/nuttx/configs/c5471evm/nsh/defconfig +++ b/nuttx/configs/c5471evm/nsh/defconfig @@ -210,21 +210,21 @@ CONFIG_NET_RESOLV_ENTRIES=4 # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_NOMAC=y -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_NOMAC=y +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/nsh @@ -241,11 +241,11 @@ CONFIG_NSH_NETMASK=0xffffff00 # # Settings for examples/wget # -CONFIG_EXAMPLE_WGET_URL="http://www.nuttx.org/index.html" -CONFIG_EXAMPLE_WGET_NOMAC=y -CONFIG_EXAMPLE_WGET_IPADDR=0x0a000002 -CONFIG_EXAMPLE_WGET_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_WGET_NETMASK=0xffffff00 +CONFIG_EXAMPLES_WGET_URL="http://www.nuttx.org/index.html" +CONFIG_EXAMPLES_WGET_NOMAC=y +CONFIG_EXAMPLES_WGET_IPADDR=0x0a000002 +CONFIG_EXAMPLES_WGET_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_WGET_NETMASK=0xffffff00 # # Stack and heap information diff --git a/nuttx/configs/c5471evm/ostest/defconfig b/nuttx/configs/c5471evm/ostest/defconfig index 4921b59e6..e0c6297c1 100644 --- a/nuttx/configs/c5471evm/ostest/defconfig +++ b/nuttx/configs/c5471evm/ostest/defconfig @@ -210,21 +210,21 @@ CONFIG_NET_RESOLV_ENTRIES=4 # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_NOMAC=y -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_NOMAC=y +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/nsh @@ -241,11 +241,11 @@ CONFIG_NSH_NETMASK=0xffffff00 # # Settings for examples/wget # -CONFIG_EXAMPLE_WGET_URL="http://www.nuttx.org/index.html" -CONFIG_EXAMPLE_WGET_NOMAC=y -CONFIG_EXAMPLE_WGET_IPADDR=0x0a000002 -CONFIG_EXAMPLE_WGET_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_WGET_NETMASK=0xffffff00 +CONFIG_EXAMPLES_WGET_URL="http://www.nuttx.org/index.html" +CONFIG_EXAMPLES_WGET_NOMAC=y +CONFIG_EXAMPLES_WGET_IPADDR=0x0a000002 +CONFIG_EXAMPLES_WGET_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_WGET_NETMASK=0xffffff00 # # Stack and heap information diff --git a/nuttx/configs/compal_e88/nsh_highram/defconfig b/nuttx/configs/compal_e88/nsh_highram/defconfig index bfb3017d2..3cf0af629 100644 --- a/nuttx/configs/compal_e88/nsh_highram/defconfig +++ b/nuttx/configs/compal_e88/nsh_highram/defconfig @@ -223,21 +223,21 @@ CONFIG_NET_RESOLV_ENTRIES=4 # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_NOMAC=y -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_NOMAC=y +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/nsh @@ -260,11 +260,11 @@ CONFIG_EXAMPLES_HELLO_BUILTIN=y # # Settings for examples/wget # -CONFIG_EXAMPLE_WGET_URL="http://www.nuttx.org/index.html" -CONFIG_EXAMPLE_WGET_NOMAC=y -CONFIG_EXAMPLE_WGET_IPADDR=0x0a000002 -CONFIG_EXAMPLE_WGET_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_WGET_NETMASK=0xffffff00 +CONFIG_EXAMPLES_WGET_URL="http://www.nuttx.org/index.html" +CONFIG_EXAMPLES_WGET_NOMAC=y +CONFIG_EXAMPLES_WGET_IPADDR=0x0a000002 +CONFIG_EXAMPLES_WGET_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_WGET_NETMASK=0xffffff00 # # Stack and heap information diff --git a/nuttx/configs/compal_e99/nsh_compalram/defconfig b/nuttx/configs/compal_e99/nsh_compalram/defconfig index 5bd924d7d..f9bf23af6 100644 --- a/nuttx/configs/compal_e99/nsh_compalram/defconfig +++ b/nuttx/configs/compal_e99/nsh_compalram/defconfig @@ -229,21 +229,21 @@ CONFIG_EXAMPLES_HELLO_BUILTIN=y # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_NOMAC=y -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_NOMAC=y +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/nsh @@ -262,11 +262,11 @@ CONFIG_NSH_BUILTIN_APPS=y # # Settings for examples/wget # -CONFIG_EXAMPLE_WGET_URL="http://www.nuttx.org/index.html" -CONFIG_EXAMPLE_WGET_NOMAC=y -CONFIG_EXAMPLE_WGET_IPADDR=0x0a000002 -CONFIG_EXAMPLE_WGET_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_WGET_NETMASK=0xffffff00 +CONFIG_EXAMPLES_WGET_URL="http://www.nuttx.org/index.html" +CONFIG_EXAMPLES_WGET_NOMAC=y +CONFIG_EXAMPLES_WGET_IPADDR=0x0a000002 +CONFIG_EXAMPLES_WGET_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_WGET_NETMASK=0xffffff00 # # Stack and heap information diff --git a/nuttx/configs/compal_e99/nsh_highram/defconfig b/nuttx/configs/compal_e99/nsh_highram/defconfig index e3f3dd816..f5323c664 100644 --- a/nuttx/configs/compal_e99/nsh_highram/defconfig +++ b/nuttx/configs/compal_e99/nsh_highram/defconfig @@ -226,21 +226,21 @@ CONFIG_NET_RESOLV_ENTRIES=4 # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_NOMAC=y -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_NOMAC=y +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/nsh @@ -306,11 +306,11 @@ CONFIG_EXAMPLES_NXTEXT_DEVNO=0 # # Settings for examples/wget # -CONFIG_EXAMPLE_WGET_URL="http://www.nuttx.org/index.html" -CONFIG_EXAMPLE_WGET_NOMAC=y -CONFIG_EXAMPLE_WGET_IPADDR=0x0a000002 -CONFIG_EXAMPLE_WGET_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_WGET_NETMASK=0xffffff00 +CONFIG_EXAMPLES_WGET_URL="http://www.nuttx.org/index.html" +CONFIG_EXAMPLES_WGET_NOMAC=y +CONFIG_EXAMPLES_WGET_IPADDR=0x0a000002 +CONFIG_EXAMPLES_WGET_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_WGET_NETMASK=0xffffff00 # # Stack and heap information diff --git a/nuttx/configs/demo9s12ne64/ostest/defconfig b/nuttx/configs/demo9s12ne64/ostest/defconfig index 6265e6e53..a45fc7e47 100755 --- a/nuttx/configs/demo9s12ne64/ostest/defconfig +++ b/nuttx/configs/demo9s12ne64/ostest/defconfig @@ -311,20 +311,20 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/ea3131/nsh/defconfig b/nuttx/configs/ea3131/nsh/defconfig index 32521f012..38caf93aa 100644 --- a/nuttx/configs/ea3131/nsh/defconfig +++ b/nuttx/configs/ea3131/nsh/defconfig @@ -312,21 +312,21 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/ea3131/ostest/defconfig b/nuttx/configs/ea3131/ostest/defconfig index 1ef35f969..abc2c8ba5 100644 --- a/nuttx/configs/ea3131/ostest/defconfig +++ b/nuttx/configs/ea3131/ostest/defconfig @@ -312,21 +312,21 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/ea3131/pgnsh/defconfig b/nuttx/configs/ea3131/pgnsh/defconfig index 995bc90d9..f03432e8d 100644 --- a/nuttx/configs/ea3131/pgnsh/defconfig +++ b/nuttx/configs/ea3131/pgnsh/defconfig @@ -355,21 +355,21 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/ea3131/usbserial/defconfig b/nuttx/configs/ea3131/usbserial/defconfig index 4e45989df..3314de254 100644 --- a/nuttx/configs/ea3131/usbserial/defconfig +++ b/nuttx/configs/ea3131/usbserial/defconfig @@ -315,21 +315,21 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/ea3131/usbstorage/defconfig b/nuttx/configs/ea3131/usbstorage/defconfig index 772de7e69..a857523df 100644 --- a/nuttx/configs/ea3131/usbstorage/defconfig +++ b/nuttx/configs/ea3131/usbstorage/defconfig @@ -316,21 +316,21 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/ea3152/ostest/defconfig b/nuttx/configs/ea3152/ostest/defconfig index 845faf60b..5b7b5b59d 100644 --- a/nuttx/configs/ea3152/ostest/defconfig +++ b/nuttx/configs/ea3152/ostest/defconfig @@ -313,21 +313,21 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/eagle100/httpd/defconfig b/nuttx/configs/eagle100/httpd/defconfig index 0fdddc2df..7c47f4467 100644 --- a/nuttx/configs/eagle100/httpd/defconfig +++ b/nuttx/configs/eagle100/httpd/defconfig @@ -263,21 +263,21 @@ CONFIG_NETUTILS_HTTPD_DUMPPSTATE=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest @@ -324,10 +324,10 @@ CONFIG_NSH_MMCSDMINOR=0 # # Settings for examples/dhcpd # -CONFIG_EXAMPLE_DHCPD_NOMAC=y -CONFIG_EXAMPLE_DHCPD_IPADDR=0x0a000001 -CONFIG_EXAMPLE_DHCPD_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_DHCPD_NETMASK=0xffffff00 +CONFIG_EXAMPLES_DHCPD_NOMAC=y +CONFIG_EXAMPLES_DHCPD_IPADDR=0x0a000001 +CONFIG_EXAMPLES_DHCPD_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_DHCPD_NETMASK=0xffffff00 # # Stack and heap information diff --git a/nuttx/configs/eagle100/nettest/defconfig b/nuttx/configs/eagle100/nettest/defconfig index 943f46223..4f2721045 100644 --- a/nuttx/configs/eagle100/nettest/defconfig +++ b/nuttx/configs/eagle100/nettest/defconfig @@ -254,21 +254,21 @@ CONFIG_NET_RESOLV_ENTRIES=4 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/eagle100/nsh/defconfig b/nuttx/configs/eagle100/nsh/defconfig index 2e04850b3..4848e957b 100644 --- a/nuttx/configs/eagle100/nsh/defconfig +++ b/nuttx/configs/eagle100/nsh/defconfig @@ -256,20 +256,20 @@ CONFIG_NET_RESOLV_ENTRIES=4 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/eagle100/nxflat/defconfig b/nuttx/configs/eagle100/nxflat/defconfig index d4228f16b..01931b0d3 100644 --- a/nuttx/configs/eagle100/nxflat/defconfig +++ b/nuttx/configs/eagle100/nxflat/defconfig @@ -258,20 +258,20 @@ CONFIG_NET_RESOLV_ENTRIES=4 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/eagle100/ostest/defconfig b/nuttx/configs/eagle100/ostest/defconfig index 6cffe1450..13a316ca4 100644 --- a/nuttx/configs/eagle100/ostest/defconfig +++ b/nuttx/configs/eagle100/ostest/defconfig @@ -252,20 +252,20 @@ CONFIG_NET_RESOLV_ENTRIES=4 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/eagle100/thttpd/defconfig b/nuttx/configs/eagle100/thttpd/defconfig index afb7dbce8..412a89e9c 100644 --- a/nuttx/configs/eagle100/thttpd/defconfig +++ b/nuttx/configs/eagle100/thttpd/defconfig @@ -289,27 +289,27 @@ CONFIG_THTTPD_URLPATTERN=n # # Additional settings for examples/thttpd # -CONFIG_EXAMPLE_THTTPD_NOMAC=n -CONFIG_EXAMPLE_THTTPD_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_THTTPD_NETMASK=0xffffff00 +CONFIG_EXAMPLES_THTTPD_NOMAC=n +CONFIG_EXAMPLES_THTTPD_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_THTTPD_NETMASK=0xffffff00 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/ekk-lm3s9b96/nsh/defconfig b/nuttx/configs/ekk-lm3s9b96/nsh/defconfig index 1e162a4a1..11407295f 100644 --- a/nuttx/configs/ekk-lm3s9b96/nsh/defconfig +++ b/nuttx/configs/ekk-lm3s9b96/nsh/defconfig @@ -271,20 +271,20 @@ CONFIG_NET_RESOLV_ENTRIES=4 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/ekk-lm3s9b96/ostest/defconfig b/nuttx/configs/ekk-lm3s9b96/ostest/defconfig index d08e99077..734ad031e 100644 --- a/nuttx/configs/ekk-lm3s9b96/ostest/defconfig +++ b/nuttx/configs/ekk-lm3s9b96/ostest/defconfig @@ -268,20 +268,20 @@ CONFIG_NET_RESOLV_ENTRIES=4 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/ez80f910200kitg/ostest/defconfig b/nuttx/configs/ez80f910200kitg/ostest/defconfig index adc92f879..22b627542 100644 --- a/nuttx/configs/ez80f910200kitg/ostest/defconfig +++ b/nuttx/configs/ez80f910200kitg/ostest/defconfig @@ -306,20 +306,20 @@ CONFIG_NX_MXCLIENTMSGS=16 # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_UIP_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_UIP_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0xc0a8006a +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0xc0a8006a # # Settings for examples/ostest @@ -386,11 +386,11 @@ CONFIG_EXAMPLES_MOUNT_DEVNAME="/dev/ram0" # # Settings for examples/wget # -CONFIG_EXAMPLE_WGET_URL="http://www.nuttx.org/index.html" -CONFIG_EXAMPLE_WGET_NOMAC=y -CONFIG_EXAMPLE_WGET_IPADDR=0x0a000002 -CONFIG_EXAMPLE_WGET_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_WGET_NETMASK=0xffffff00 +CONFIG_EXAMPLES_WGET_URL="http://www.nuttx.org/index.html" +CONFIG_EXAMPLES_WGET_NOMAC=y +CONFIG_EXAMPLES_WGET_IPADDR=0x0a000002 +CONFIG_EXAMPLES_WGET_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_WGET_NETMASK=0xffffff00 # # Stack and heap information diff --git a/nuttx/configs/ez80f910200zco/dhcpd/defconfig b/nuttx/configs/ez80f910200zco/dhcpd/defconfig index 8f7b6479f..ea9844dc2 100644 --- a/nuttx/configs/ez80f910200zco/dhcpd/defconfig +++ b/nuttx/configs/ez80f910200zco/dhcpd/defconfig @@ -312,28 +312,28 @@ CONFIG_NX_MXCLIENTMSGS=16 # # Settings for examples/poll -CONFIG_EXAMPLE_POLL_NOMAC=y -CONFIG_EXAMPLE_POLL_IPADDR=0x0a000002 -CONFIG_EXAMPLE_POLL_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_POLL_NETMASK=0xffffff00 +CONFIG_EXAMPLES_POLL_NOMAC=y +CONFIG_EXAMPLES_POLL_IPADDR=0x0a000002 +CONFIG_EXAMPLES_POLL_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_POLL_NETMASK=0xffffff00 # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest @@ -376,10 +376,10 @@ CONFIG_NSH_MMCSDMINOR=0 # # Settings for examples/dhcpd -CONFIG_EXAMPLE_DHCPD_NOMAC=y -CONFIG_EXAMPLE_DHCPD_IPADDR=0x0a000001 -CONFIG_EXAMPLE_DHCPD_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_DHCPD_NETMASK=0xffffff00 +CONFIG_EXAMPLES_DHCPD_NOMAC=y +CONFIG_EXAMPLES_DHCPD_IPADDR=0x0a000001 +CONFIG_EXAMPLES_DHCPD_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_DHCPD_NETMASK=0xffffff00 # # Settings for examples/nx @@ -407,11 +407,11 @@ CONFIG_EXAMPLES_MOUNT_DEVNAME="/dev/ram0" # # Settings for examples/wget # -CONFIG_EXAMPLE_WGET_URL="http://www.nuttx.org/index.html" -CONFIG_EXAMPLE_WGET_NOMAC=y -CONFIG_EXAMPLE_WGET_IPADDR=0x0a000002 -CONFIG_EXAMPLE_WGET_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_WGET_NETMASK=0xffffff00 +CONFIG_EXAMPLES_WGET_URL="http://www.nuttx.org/index.html" +CONFIG_EXAMPLES_WGET_NOMAC=y +CONFIG_EXAMPLES_WGET_IPADDR=0x0a000002 +CONFIG_EXAMPLES_WGET_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_WGET_NETMASK=0xffffff00 # # Stack and heap information diff --git a/nuttx/configs/ez80f910200zco/httpd/defconfig b/nuttx/configs/ez80f910200zco/httpd/defconfig index 296521a9e..ddf34285a 100644 --- a/nuttx/configs/ez80f910200zco/httpd/defconfig +++ b/nuttx/configs/ez80f910200zco/httpd/defconfig @@ -320,28 +320,28 @@ CONFIG_NETUTILS_HTTPD_DUMPPSTATE=n # # Settings for examples/poll -CONFIG_EXAMPLE_POLL_NOMAC=y -CONFIG_EXAMPLE_POLL_IPADDR=0x0a000002 -CONFIG_EXAMPLE_POLL_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_POLL_NETMASK=0xffffff00 +CONFIG_EXAMPLES_POLL_NOMAC=y +CONFIG_EXAMPLES_POLL_IPADDR=0x0a000002 +CONFIG_EXAMPLES_POLL_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_POLL_NETMASK=0xffffff00 # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest @@ -384,10 +384,10 @@ CONFIG_NSH_MMCSDMINOR=0 # # Settings for examples/dhcpd -CONFIG_EXAMPLE_DHCPD_NOMAC=y -CONFIG_EXAMPLE_DHCPD_IPADDR=0x0a000001 -CONFIG_EXAMPLE_DHCPD_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_DHCPD_NETMASK=0xffffff00 +CONFIG_EXAMPLES_DHCPD_NOMAC=y +CONFIG_EXAMPLES_DHCPD_IPADDR=0x0a000001 +CONFIG_EXAMPLES_DHCPD_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_DHCPD_NETMASK=0xffffff00 # # Settings for examples/nx @@ -415,11 +415,11 @@ CONFIG_EXAMPLES_MOUNT_DEVNAME="/dev/ram0" # # Settings for examples/wget # -CONFIG_EXAMPLE_WGET_URL="http://www.nuttx.org/index.html" -CONFIG_EXAMPLE_WGET_NOMAC=y -CONFIG_EXAMPLE_WGET_IPADDR=0x0a000002 -CONFIG_EXAMPLE_WGET_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_WGET_NETMASK=0xffffff00 +CONFIG_EXAMPLES_WGET_URL="http://www.nuttx.org/index.html" +CONFIG_EXAMPLES_WGET_NOMAC=y +CONFIG_EXAMPLES_WGET_IPADDR=0x0a000002 +CONFIG_EXAMPLES_WGET_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_WGET_NETMASK=0xffffff00 # # Stack and heap information diff --git a/nuttx/configs/ez80f910200zco/nettest/defconfig b/nuttx/configs/ez80f910200zco/nettest/defconfig index fb424a766..7b1415bf4 100644 --- a/nuttx/configs/ez80f910200zco/nettest/defconfig +++ b/nuttx/configs/ez80f910200zco/nettest/defconfig @@ -312,28 +312,28 @@ CONFIG_NX_MXCLIENTMSGS=16 # # Settings for examples/poll -CONFIG_EXAMPLE_POLL_NOMAC=y -CONFIG_EXAMPLE_POLL_IPADDR=0x0a000002 -CONFIG_EXAMPLE_POLL_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_POLL_NETMASK=0xffffff00 +CONFIG_EXAMPLES_POLL_NOMAC=y +CONFIG_EXAMPLES_POLL_IPADDR=0x0a000002 +CONFIG_EXAMPLES_POLL_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_POLL_NETMASK=0xffffff00 # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest @@ -400,11 +400,11 @@ CONFIG_EXAMPLES_MOUNT_DEVNAME="/dev/ram0" # # Settings for examples/wget # -CONFIG_EXAMPLE_WGET_URL="http://www.nuttx.org/index.html" -CONFIG_EXAMPLE_WGET_NOMAC=y -CONFIG_EXAMPLE_WGET_IPADDR=0x0a000002 -CONFIG_EXAMPLE_WGET_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_WGET_NETMASK=0xffffff00 +CONFIG_EXAMPLES_WGET_URL="http://www.nuttx.org/index.html" +CONFIG_EXAMPLES_WGET_NOMAC=y +CONFIG_EXAMPLES_WGET_IPADDR=0x0a000002 +CONFIG_EXAMPLES_WGET_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_WGET_NETMASK=0xffffff00 # # Stack and heap information diff --git a/nuttx/configs/ez80f910200zco/nsh/defconfig b/nuttx/configs/ez80f910200zco/nsh/defconfig index 9c4b5aaee..fa701253d 100644 --- a/nuttx/configs/ez80f910200zco/nsh/defconfig +++ b/nuttx/configs/ez80f910200zco/nsh/defconfig @@ -312,28 +312,28 @@ CONFIG_NX_MXCLIENTMSGS=16 # # Settings for examples/poll -CONFIG_EXAMPLE_POLL_NOMAC=y -CONFIG_EXAMPLE_POLL_IPADDR=0x0a000002 -CONFIG_EXAMPLE_POLL_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_POLL_NETMASK=0xffffff00 +CONFIG_EXAMPLES_POLL_NOMAC=y +CONFIG_EXAMPLES_POLL_IPADDR=0x0a000002 +CONFIG_EXAMPLES_POLL_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_POLL_NETMASK=0xffffff00 # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest @@ -400,11 +400,11 @@ CONFIG_EXAMPLES_MOUNT_DEVNAME="/dev/ram0" # # Settings for examples/wget # -CONFIG_EXAMPLE_WGET_URL="http://www.nuttx.org/index.html" -CONFIG_EXAMPLE_WGET_NOMAC=y -CONFIG_EXAMPLE_WGET_IPADDR=0x0a000002 -CONFIG_EXAMPLE_WGET_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_WGET_NETMASK=0xffffff00 +CONFIG_EXAMPLES_WGET_URL="http://www.nuttx.org/index.html" +CONFIG_EXAMPLES_WGET_NOMAC=y +CONFIG_EXAMPLES_WGET_IPADDR=0x0a000002 +CONFIG_EXAMPLES_WGET_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_WGET_NETMASK=0xffffff00 # # Stack and heap information diff --git a/nuttx/configs/ez80f910200zco/ostest/defconfig b/nuttx/configs/ez80f910200zco/ostest/defconfig index 548ce3376..f16ddee39 100644 --- a/nuttx/configs/ez80f910200zco/ostest/defconfig +++ b/nuttx/configs/ez80f910200zco/ostest/defconfig @@ -308,27 +308,27 @@ CONFIG_NX_MXCLIENTMSGS=16 # # Settings for examples/poll -CONFIG_EXAMPLE_POLL_NOMAC=y -CONFIG_EXAMPLE_POLL_IPADDR=0x0a000002 -CONFIG_EXAMPLE_POLL_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_POLL_NETMASK=0xffffff00 +CONFIG_EXAMPLES_POLL_NOMAC=y +CONFIG_EXAMPLES_POLL_IPADDR=0x0a000002 +CONFIG_EXAMPLES_POLL_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_POLL_NETMASK=0xffffff00 # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_UIP_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_UIP_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0xc0a8006a +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0xc0a8006a # # Settings for examples/ostest @@ -395,11 +395,11 @@ CONFIG_EXAMPLES_MOUNT_DEVNAME="/dev/ram0" # # Settings for examples/wget # -CONFIG_EXAMPLE_WGET_URL="http://www.nuttx.org/index.html" -CONFIG_EXAMPLE_WGET_NOMAC=y -CONFIG_EXAMPLE_WGET_IPADDR=0x0a000002 -CONFIG_EXAMPLE_WGET_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_WGET_NETMASK=0xffffff00 +CONFIG_EXAMPLES_WGET_URL="http://www.nuttx.org/index.html" +CONFIG_EXAMPLES_WGET_NOMAC=y +CONFIG_EXAMPLES_WGET_IPADDR=0x0a000002 +CONFIG_EXAMPLES_WGET_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_WGET_NETMASK=0xffffff00 # # Stack and heap information diff --git a/nuttx/configs/ez80f910200zco/poll/defconfig b/nuttx/configs/ez80f910200zco/poll/defconfig index 0334ebc26..6ad505dc5 100644 --- a/nuttx/configs/ez80f910200zco/poll/defconfig +++ b/nuttx/configs/ez80f910200zco/poll/defconfig @@ -312,28 +312,28 @@ CONFIG_NX_MXCLIENTMSGS=16 # # Settings for examples/poll -CONFIG_EXAMPLE_POLL_NOMAC=y -CONFIG_EXAMPLE_POLL_IPADDR=0x0a000002 -CONFIG_EXAMPLE_POLL_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_POLL_NETMASK=0xffffff00 +CONFIG_EXAMPLES_POLL_NOMAC=y +CONFIG_EXAMPLES_POLL_IPADDR=0x0a000002 +CONFIG_EXAMPLES_POLL_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_POLL_NETMASK=0xffffff00 # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest @@ -400,11 +400,11 @@ CONFIG_EXAMPLES_MOUNT_DEVNAME="/dev/ram0" # # Settings for examples/wget # -CONFIG_EXAMPLE_WGET_URL="http://www.nuttx.org/index.html" -CONFIG_EXAMPLE_WGET_NOMAC=y -CONFIG_EXAMPLE_WGET_IPADDR=0x0a000002 -CONFIG_EXAMPLE_WGET_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_WGET_NETMASK=0xffffff00 +CONFIG_EXAMPLES_WGET_URL="http://www.nuttx.org/index.html" +CONFIG_EXAMPLES_WGET_NOMAC=y +CONFIG_EXAMPLES_WGET_IPADDR=0x0a000002 +CONFIG_EXAMPLES_WGET_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_WGET_NETMASK=0xffffff00 # # Stack and heap information diff --git a/nuttx/configs/fire-stm32v2/nsh/defconfig b/nuttx/configs/fire-stm32v2/nsh/defconfig index 25e782dfe..5edde6ed1 100644 --- a/nuttx/configs/fire-stm32v2/nsh/defconfig +++ b/nuttx/configs/fire-stm32v2/nsh/defconfig @@ -751,7 +751,7 @@ CONFIG_EXAMPLES_NSH=y # # UDP Discovery Daemon Example # -# CONFIG_EXAMPLE_DISCOVER is not set +# CONFIG_EXAMPLES_DISCOVER is not set # # uIP Web Server Example diff --git a/nuttx/configs/hymini-stm32v/buttons/defconfig b/nuttx/configs/hymini-stm32v/buttons/defconfig index 59b7b111f..44dcf3c41 100644 --- a/nuttx/configs/hymini-stm32v/buttons/defconfig +++ b/nuttx/configs/hymini-stm32v/buttons/defconfig @@ -373,36 +373,36 @@ CONFIG_WATCHDOG=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/buttons # -CONFIG_EXAMPLE_BUTTONS_MIN=0 -CONFIG_EXAMPLE_BUTTONS_MAX=7 -CONFIG_EXAMPLE_IRQBUTTONS_MIN=2 -CONFIG_EXAMPLE_IRQBUTTONS_MAX=7 -CONFIG_EXAMPLE_BUTTONS_NAME0="WAKEUP" -CONFIG_EXAMPLE_BUTTONS_NAME1="TAMPER" -CONFIG_EXAMPLE_BUTTONS_NAME2="KEY" -CONFIG_EXAMPLE_BUTTONS_NAME3="SELECT" -CONFIG_EXAMPLE_BUTTONS_NAME4="DOWN" -CONFIG_EXAMPLE_BUTTONS_NAME5="LEFT" -CONFIG_EXAMPLE_BUTTONS_NAME6="RIGHT" -CONFIG_EXAMPLE_BUTTONS_NAME7="UP" +CONFIG_EXAMPLES_BUTTONS_MIN=0 +CONFIG_EXAMPLES_BUTTONS_MAX=7 +CONFIG_EXAMPLES_IRQBUTTONS_MIN=2 +CONFIG_EXAMPLES_IRQBUTTONS_MAX=7 +CONFIG_EXAMPLES_BUTTONS_NAME0="WAKEUP" +CONFIG_EXAMPLES_BUTTONS_NAME1="TAMPER" +CONFIG_EXAMPLES_BUTTONS_NAME2="KEY" +CONFIG_EXAMPLES_BUTTONS_NAME3="SELECT" +CONFIG_EXAMPLES_BUTTONS_NAME4="DOWN" +CONFIG_EXAMPLES_BUTTONS_NAME5="LEFT" +CONFIG_EXAMPLES_BUTTONS_NAME6="RIGHT" +CONFIG_EXAMPLES_BUTTONS_NAME7="UP" # # Settings for examples/ostest diff --git a/nuttx/configs/hymini-stm32v/nsh/defconfig b/nuttx/configs/hymini-stm32v/nsh/defconfig index 1b0944d02..52da9f6f6 100755 --- a/nuttx/configs/hymini-stm32v/nsh/defconfig +++ b/nuttx/configs/hymini-stm32v/nsh/defconfig @@ -373,20 +373,20 @@ CONFIG_WATCHDOG=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/hymini-stm32v/nx/defconfig b/nuttx/configs/hymini-stm32v/nx/defconfig index 645feac1b..e411baf83 100644 --- a/nuttx/configs/hymini-stm32v/nx/defconfig +++ b/nuttx/configs/hymini-stm32v/nx/defconfig @@ -435,20 +435,20 @@ CONFIG_LCD_BACKLIGHT=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/hymini-stm32v/usbserial/defconfig b/nuttx/configs/hymini-stm32v/usbserial/defconfig index 379e51a5e..7883db827 100755 --- a/nuttx/configs/hymini-stm32v/usbserial/defconfig +++ b/nuttx/configs/hymini-stm32v/usbserial/defconfig @@ -395,20 +395,20 @@ CONFIG_WATCHDOG=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/hymini-stm32v/usbstorage/defconfig b/nuttx/configs/hymini-stm32v/usbstorage/defconfig index b56f62754..c3434e3a4 100755 --- a/nuttx/configs/hymini-stm32v/usbstorage/defconfig +++ b/nuttx/configs/hymini-stm32v/usbstorage/defconfig @@ -380,20 +380,20 @@ CONFIG_WATCHDOG=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/kwikstik-k40/ostest/defconfig b/nuttx/configs/kwikstik-k40/ostest/defconfig index 29bed1244..2cf29894b 100755 --- a/nuttx/configs/kwikstik-k40/ostest/defconfig +++ b/nuttx/configs/kwikstik-k40/ostest/defconfig @@ -377,20 +377,20 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/lincoln60/nsh/defconfig b/nuttx/configs/lincoln60/nsh/defconfig index a120e2c74..43944f0a6 100644 --- a/nuttx/configs/lincoln60/nsh/defconfig +++ b/nuttx/configs/lincoln60/nsh/defconfig @@ -359,20 +359,20 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/lincoln60/ostest/defconfig b/nuttx/configs/lincoln60/ostest/defconfig index 6c74a9f54..6dd51eb07 100644 --- a/nuttx/configs/lincoln60/ostest/defconfig +++ b/nuttx/configs/lincoln60/ostest/defconfig @@ -369,21 +369,21 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest @@ -395,18 +395,18 @@ CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=3 # # Settings for examples/buttons # -CONFIG_EXAMPLE_BUTTONS_MIN=0 -CONFIG_EXAMPLE_BUTTONS_MAX=7 -CONFIG_EXAMPLE_IRQBUTTONS_MIN=0 -CONFIG_EXAMPLE_IRQBUTTONS_MAX=7 -CONFIG_EXAMPLE_BUTTONS_NAME0="BUT1" -CONFIG_EXAMPLE_BUTTONS_NAME1="BUT2" -CONFIG_EXAMPLE_BUTTONS_NAME2="WAKE-UP" -CONFIG_EXAMPLE_BUTTONS_NAME3="CENTER" -CONFIG_EXAMPLE_BUTTONS_NAME4="UP" -CONFIG_EXAMPLE_BUTTONS_NAME5="DOWN" -CONFIG_EXAMPLE_BUTTONS_NAME6="LEFT" -CONFIG_EXAMPLE_BUTTONS_NAME7="RIGHT" +CONFIG_EXAMPLES_BUTTONS_MIN=0 +CONFIG_EXAMPLES_BUTTONS_MAX=7 +CONFIG_EXAMPLES_IRQBUTTONS_MIN=0 +CONFIG_EXAMPLES_IRQBUTTONS_MAX=7 +CONFIG_EXAMPLES_BUTTONS_NAME0="BUT1" +CONFIG_EXAMPLES_BUTTONS_NAME1="BUT2" +CONFIG_EXAMPLES_BUTTONS_NAME2="WAKE-UP" +CONFIG_EXAMPLES_BUTTONS_NAME3="CENTER" +CONFIG_EXAMPLES_BUTTONS_NAME4="UP" +CONFIG_EXAMPLES_BUTTONS_NAME5="DOWN" +CONFIG_EXAMPLES_BUTTONS_NAME6="LEFT" +CONFIG_EXAMPLES_BUTTONS_NAME7="RIGHT" # # Settings for apps/nshlib diff --git a/nuttx/configs/lm3s6432-s2e/nsh/defconfig b/nuttx/configs/lm3s6432-s2e/nsh/defconfig index b4dd453ac..f0cf503ef 100644 --- a/nuttx/configs/lm3s6432-s2e/nsh/defconfig +++ b/nuttx/configs/lm3s6432-s2e/nsh/defconfig @@ -271,20 +271,20 @@ CONFIG_NET_RESOLV_ENTRIES=4 # # Settings for examples/uip # -#CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -#CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -#CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=y +#CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +#CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +#CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=y # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/lm3s6432-s2e/ostest/defconfig b/nuttx/configs/lm3s6432-s2e/ostest/defconfig index e04f3da8d..daeac0177 100644 --- a/nuttx/configs/lm3s6432-s2e/ostest/defconfig +++ b/nuttx/configs/lm3s6432-s2e/ostest/defconfig @@ -268,20 +268,20 @@ CONFIG_NET_RESOLV_ENTRIES=4 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/lm3s6965-ek/nsh/defconfig b/nuttx/configs/lm3s6965-ek/nsh/defconfig index bfad857f0..2771a3dc9 100755 --- a/nuttx/configs/lm3s6965-ek/nsh/defconfig +++ b/nuttx/configs/lm3s6965-ek/nsh/defconfig @@ -273,20 +273,20 @@ CONFIG_NET_RESOLV_ENTRIES=4 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/lm3s6965-ek/nx/defconfig b/nuttx/configs/lm3s6965-ek/nx/defconfig index 4bc7d73a6..83b338161 100755 --- a/nuttx/configs/lm3s6965-ek/nx/defconfig +++ b/nuttx/configs/lm3s6965-ek/nx/defconfig @@ -322,20 +322,20 @@ CONFIG_P14201_FRAMEBUFFER=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/lm3s6965-ek/ostest/defconfig b/nuttx/configs/lm3s6965-ek/ostest/defconfig index 8aeef4a00..0bfe9ef72 100755 --- a/nuttx/configs/lm3s6965-ek/ostest/defconfig +++ b/nuttx/configs/lm3s6965-ek/ostest/defconfig @@ -269,20 +269,20 @@ CONFIG_NET_RESOLV_ENTRIES=4 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/lm3s8962-ek/nsh/defconfig b/nuttx/configs/lm3s8962-ek/nsh/defconfig index 8c3d834f5..001a87387 100755 --- a/nuttx/configs/lm3s8962-ek/nsh/defconfig +++ b/nuttx/configs/lm3s8962-ek/nsh/defconfig @@ -271,20 +271,20 @@ CONFIG_NET_RESOLV_ENTRIES=4 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/lm3s8962-ek/nx/defconfig b/nuttx/configs/lm3s8962-ek/nx/defconfig index 49bbe0675..dbae4b2aa 100755 --- a/nuttx/configs/lm3s8962-ek/nx/defconfig +++ b/nuttx/configs/lm3s8962-ek/nx/defconfig @@ -320,20 +320,20 @@ CONFIG_P14201_FRAMEBUFFER=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/lm3s8962-ek/ostest/defconfig b/nuttx/configs/lm3s8962-ek/ostest/defconfig index adb806b9c..aeb0a1ecf 100755 --- a/nuttx/configs/lm3s8962-ek/ostest/defconfig +++ b/nuttx/configs/lm3s8962-ek/ostest/defconfig @@ -268,20 +268,20 @@ CONFIG_NET_RESOLV_ENTRIES=4 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/lpc4330-xplorer/nsh/defconfig b/nuttx/configs/lpc4330-xplorer/nsh/defconfig index 406f6f2ba..e4269ea67 100644 --- a/nuttx/configs/lpc4330-xplorer/nsh/defconfig +++ b/nuttx/configs/lpc4330-xplorer/nsh/defconfig @@ -468,21 +468,21 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest @@ -541,11 +541,11 @@ CONFIG_I2CTOOL_DEFFREQ=100000 # # Settings for examples/buttons # -CONFIG_EXAMPLE_BUTTONS_MIN=0 -CONFIG_EXAMPLE_BUTTONS_MAX=0 -CONFIG_EXAMPLE_IRQBUTTONS_MIN=0 -CONFIG_EXAMPLE_IRQBUTTONS_MAX=0 -CONFIG_EXAMPLE_BUTTONS_NAME1="SW2" +CONFIG_EXAMPLES_BUTTONS_MIN=0 +CONFIG_EXAMPLES_BUTTONS_MAX=0 +CONFIG_EXAMPLES_IRQBUTTONS_MIN=0 +CONFIG_EXAMPLES_IRQBUTTONS_MAX=0 +CONFIG_EXAMPLES_BUTTONS_NAME1="SW2" # # examples/modbus diff --git a/nuttx/configs/lpc4330-xplorer/ostest/defconfig b/nuttx/configs/lpc4330-xplorer/ostest/defconfig index 560e3327b..d5ac58ef1 100644 --- a/nuttx/configs/lpc4330-xplorer/ostest/defconfig +++ b/nuttx/configs/lpc4330-xplorer/ostest/defconfig @@ -452,20 +452,20 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest @@ -524,11 +524,11 @@ CONFIG_I2CTOOL_DEFFREQ=100000 # # Settings for examples/buttons # -CONFIG_EXAMPLE_BUTTONS_MIN=0 -CONFIG_EXAMPLE_BUTTONS_MAX=0 -CONFIG_EXAMPLE_IRQBUTTONS_MIN=0 -CONFIG_EXAMPLE_IRQBUTTONS_MAX=0 -CONFIG_EXAMPLE_BUTTONS_NAME1="SW2" +CONFIG_EXAMPLES_BUTTONS_MIN=0 +CONFIG_EXAMPLES_BUTTONS_MAX=0 +CONFIG_EXAMPLES_IRQBUTTONS_MIN=0 +CONFIG_EXAMPLES_IRQBUTTONS_MAX=0 +CONFIG_EXAMPLES_BUTTONS_NAME1="SW2" # # Settings for examples/usbserial diff --git a/nuttx/configs/lpcxpresso-lpc1768/dhcpd/defconfig b/nuttx/configs/lpcxpresso-lpc1768/dhcpd/defconfig index 0b7f1c153..01c54fa9f 100755 --- a/nuttx/configs/lpcxpresso-lpc1768/dhcpd/defconfig +++ b/nuttx/configs/lpcxpresso-lpc1768/dhcpd/defconfig @@ -375,29 +375,29 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/dhcpd # -CONFIG_EXAMPLE_DHCPD_NOMAC=y -CONFIG_EXAMPLE_DHCPD_IPADDR=0x0a000001 -CONFIG_EXAMPLE_DHCPD_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_DHCPD_NETMASK=0xffffff00 +CONFIG_EXAMPLES_DHCPD_NOMAC=y +CONFIG_EXAMPLES_DHCPD_IPADDR=0x0a000001 +CONFIG_EXAMPLES_DHCPD_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_DHCPD_NETMASK=0xffffff00 # # Settings for examples/ostest diff --git a/nuttx/configs/lpcxpresso-lpc1768/nsh/defconfig b/nuttx/configs/lpcxpresso-lpc1768/nsh/defconfig index cb78f88cc..6d0be8400 100755 --- a/nuttx/configs/lpcxpresso-lpc1768/nsh/defconfig +++ b/nuttx/configs/lpcxpresso-lpc1768/nsh/defconfig @@ -393,21 +393,21 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/lpcxpresso-lpc1768/nx/defconfig b/nuttx/configs/lpcxpresso-lpc1768/nx/defconfig index 54c6828a8..a94571a83 100755 --- a/nuttx/configs/lpcxpresso-lpc1768/nx/defconfig +++ b/nuttx/configs/lpcxpresso-lpc1768/nx/defconfig @@ -426,21 +426,21 @@ CONFIG_UG9664HSWAG01_POWER=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/lpcxpresso-lpc1768/ostest/defconfig b/nuttx/configs/lpcxpresso-lpc1768/ostest/defconfig index a808333ff..f58c78773 100755 --- a/nuttx/configs/lpcxpresso-lpc1768/ostest/defconfig +++ b/nuttx/configs/lpcxpresso-lpc1768/ostest/defconfig @@ -371,21 +371,21 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/lpcxpresso-lpc1768/thttpd/defconfig b/nuttx/configs/lpcxpresso-lpc1768/thttpd/defconfig index 227bbdebd..08d251d43 100755 --- a/nuttx/configs/lpcxpresso-lpc1768/thttpd/defconfig +++ b/nuttx/configs/lpcxpresso-lpc1768/thttpd/defconfig @@ -403,28 +403,28 @@ CONFIG_THTTPD_URLPATTERN=n # # Additional settings for examples/thttpd # -CONFIG_EXAMPLE_THTTPD_NOMAC=y -CONFIG_EXAMPLE_THTTPD_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_THTTPD_NETMASK=0xffffff00 +CONFIG_EXAMPLES_THTTPD_NOMAC=y +CONFIG_EXAMPLES_THTTPD_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_THTTPD_NETMASK=0xffffff00 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/lpcxpresso-lpc1768/usbstorage/defconfig b/nuttx/configs/lpcxpresso-lpc1768/usbstorage/defconfig index 4aca6768c..08f4ad1cf 100755 --- a/nuttx/configs/lpcxpresso-lpc1768/usbstorage/defconfig +++ b/nuttx/configs/lpcxpresso-lpc1768/usbstorage/defconfig @@ -367,21 +367,21 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/mbed/hidkbd/defconfig b/nuttx/configs/mbed/hidkbd/defconfig index edcf8e181..3ec691276 100644 --- a/nuttx/configs/mbed/hidkbd/defconfig +++ b/nuttx/configs/mbed/hidkbd/defconfig @@ -387,21 +387,21 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/mbed/nsh/defconfig b/nuttx/configs/mbed/nsh/defconfig index c1a35e4b1..dba89ec7b 100755 --- a/nuttx/configs/mbed/nsh/defconfig +++ b/nuttx/configs/mbed/nsh/defconfig @@ -359,20 +359,20 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/micropendous3/hello/defconfig b/nuttx/configs/micropendous3/hello/defconfig index 4563a12e3..4e0ea0e99 100644 --- a/nuttx/configs/micropendous3/hello/defconfig +++ b/nuttx/configs/micropendous3/hello/defconfig @@ -313,21 +313,21 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/mirtoo/nsh/defconfig b/nuttx/configs/mirtoo/nsh/defconfig index c210c134b..4e3cb684e 100644 --- a/nuttx/configs/mirtoo/nsh/defconfig +++ b/nuttx/configs/mirtoo/nsh/defconfig @@ -396,21 +396,21 @@ CONFIG_PGA11X_MULTIPLE=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/mirtoo/nxffs/defconfig b/nuttx/configs/mirtoo/nxffs/defconfig index 1dbb2c02c..31e3ef89b 100644 --- a/nuttx/configs/mirtoo/nxffs/defconfig +++ b/nuttx/configs/mirtoo/nxffs/defconfig @@ -395,21 +395,21 @@ CONFIG_PGA11X_MULTIPLE=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/mirtoo/ostest/defconfig b/nuttx/configs/mirtoo/ostest/defconfig index 702b01bc8..a3af96fbc 100644 --- a/nuttx/configs/mirtoo/ostest/defconfig +++ b/nuttx/configs/mirtoo/ostest/defconfig @@ -372,21 +372,21 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/mx1ads/ostest/defconfig b/nuttx/configs/mx1ads/ostest/defconfig index c699aab51..9e425975d 100644 --- a/nuttx/configs/mx1ads/ostest/defconfig +++ b/nuttx/configs/mx1ads/ostest/defconfig @@ -270,20 +270,20 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/nsh diff --git a/nuttx/configs/ne64badge/ostest/defconfig b/nuttx/configs/ne64badge/ostest/defconfig index 59f52f661..ee36399f1 100755 --- a/nuttx/configs/ne64badge/ostest/defconfig +++ b/nuttx/configs/ne64badge/ostest/defconfig @@ -317,20 +317,20 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/ntosd-dm320/nettest/defconfig b/nuttx/configs/ntosd-dm320/nettest/defconfig index 848cf2f9d..178638054 100644 --- a/nuttx/configs/ntosd-dm320/nettest/defconfig +++ b/nuttx/configs/ntosd-dm320/nettest/defconfig @@ -266,20 +266,20 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/nsh diff --git a/nuttx/configs/ntosd-dm320/nsh/defconfig b/nuttx/configs/ntosd-dm320/nsh/defconfig index d824f55fc..33cf33c24 100644 --- a/nuttx/configs/ntosd-dm320/nsh/defconfig +++ b/nuttx/configs/ntosd-dm320/nsh/defconfig @@ -271,20 +271,20 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/ntosd-dm320/ostest/defconfig b/nuttx/configs/ntosd-dm320/ostest/defconfig index edc991880..52ebe0bd9 100644 --- a/nuttx/configs/ntosd-dm320/ostest/defconfig +++ b/nuttx/configs/ntosd-dm320/ostest/defconfig @@ -262,20 +262,20 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/nsh diff --git a/nuttx/configs/ntosd-dm320/poll/defconfig b/nuttx/configs/ntosd-dm320/poll/defconfig index 7386ff966..f27dcc2c3 100644 --- a/nuttx/configs/ntosd-dm320/poll/defconfig +++ b/nuttx/configs/ntosd-dm320/poll/defconfig @@ -266,27 +266,27 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/poll -CONFIG_EXAMPLE_POLL_NOMAC=n -CONFIG_EXAMPLE_POLL_IPADDR=0x0a000002 -CONFIG_EXAMPLE_POLL_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_POLL_NETMASK=0xffffff00 +CONFIG_EXAMPLES_POLL_NOMAC=n +CONFIG_EXAMPLES_POLL_IPADDR=0x0a000002 +CONFIG_EXAMPLES_POLL_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_POLL_NETMASK=0xffffff00 # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/nsh diff --git a/nuttx/configs/ntosd-dm320/thttpd/defconfig b/nuttx/configs/ntosd-dm320/thttpd/defconfig index 90f84c5e3..becec2ef1 100644 --- a/nuttx/configs/ntosd-dm320/thttpd/defconfig +++ b/nuttx/configs/ntosd-dm320/thttpd/defconfig @@ -318,26 +318,26 @@ CONFIG_THTTPD_URLPATTERN=n # # Additional settings for examples/thttpd # -CONFIG_EXAMPLE_THTTPD_NOMAC=n -CONFIG_EXAMPLE_THTTPD_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_THTTPD_NETMASK=0xffffff00 +CONFIG_EXAMPLES_THTTPD_NOMAC=n +CONFIG_EXAMPLES_THTTPD_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_THTTPD_NETMASK=0xffffff00 # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/nsh diff --git a/nuttx/configs/ntosd-dm320/udp/defconfig b/nuttx/configs/ntosd-dm320/udp/defconfig index 4bc4b4bc8..869f2e442 100644 --- a/nuttx/configs/ntosd-dm320/udp/defconfig +++ b/nuttx/configs/ntosd-dm320/udp/defconfig @@ -266,28 +266,28 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/udp -CONFIG_EXAMPLE_UDP_SERVER=n -CONFIG_EXAMPLE_UDP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UDP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UDP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UDP_SERVERIP=0x0a000001 +CONFIG_EXAMPLES_UDP_SERVER=n +CONFIG_EXAMPLES_UDP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UDP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UDP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UDP_SERVERIP=0x0a000001 # # Settings for examples/nsh diff --git a/nuttx/configs/ntosd-dm320/uip/defconfig b/nuttx/configs/ntosd-dm320/uip/defconfig index 88a45f94d..19ffe452a 100644 --- a/nuttx/configs/ntosd-dm320/uip/defconfig +++ b/nuttx/configs/ntosd-dm320/uip/defconfig @@ -274,20 +274,20 @@ CONFIG_NETUTILS_HTTPD_DUMPPSTATE=n # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/nsh diff --git a/nuttx/configs/nucleus2g/nsh/defconfig b/nuttx/configs/nucleus2g/nsh/defconfig index 9397820cd..080c48770 100755 --- a/nuttx/configs/nucleus2g/nsh/defconfig +++ b/nuttx/configs/nucleus2g/nsh/defconfig @@ -381,21 +381,21 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/nucleus2g/ostest/defconfig b/nuttx/configs/nucleus2g/ostest/defconfig index 848fafdba..02eb31633 100755 --- a/nuttx/configs/nucleus2g/ostest/defconfig +++ b/nuttx/configs/nucleus2g/ostest/defconfig @@ -359,20 +359,20 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/nucleus2g/usbserial/defconfig b/nuttx/configs/nucleus2g/usbserial/defconfig index d0decf903..300d30ab3 100755 --- a/nuttx/configs/nucleus2g/usbserial/defconfig +++ b/nuttx/configs/nucleus2g/usbserial/defconfig @@ -360,20 +360,20 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/nucleus2g/usbstorage/defconfig b/nuttx/configs/nucleus2g/usbstorage/defconfig index ec79e8fd3..7887818fb 100755 --- a/nuttx/configs/nucleus2g/usbstorage/defconfig +++ b/nuttx/configs/nucleus2g/usbstorage/defconfig @@ -361,20 +361,20 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/olimex-lpc1766stk/ftpc/defconfig b/nuttx/configs/olimex-lpc1766stk/ftpc/defconfig index 3498195b1..6d1375e92 100755 --- a/nuttx/configs/olimex-lpc1766stk/ftpc/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/ftpc/defconfig @@ -433,28 +433,28 @@ CONFIG_THTTPD_URLPATTERN=n # # Additional settings for examples/thttpd # -CONFIG_EXAMPLE_THTTPD_NOMAC=y -CONFIG_EXAMPLE_THTTPD_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_THTTPD_NETMASK=0xffffff00 +CONFIG_EXAMPLES_THTTPD_NOMAC=y +CONFIG_EXAMPLES_THTTPD_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_THTTPD_NETMASK=0xffffff00 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest @@ -466,18 +466,18 @@ CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=3 # # Settings for examples/buttons # -CONFIG_EXAMPLE_BUTTONS_MIN=0 -CONFIG_EXAMPLE_BUTTONS_MAX=7 -CONFIG_EXAMPLE_IRQBUTTONS_MIN=0 -CONFIG_EXAMPLE_IRQBUTTONS_MAX=7 -CONFIG_EXAMPLE_BUTTONS_NAME0="BUT1" -CONFIG_EXAMPLE_BUTTONS_NAME1="BUT2" -CONFIG_EXAMPLE_BUTTONS_NAME2="WAKE-UP" -CONFIG_EXAMPLE_BUTTONS_NAME3="CENTER" -CONFIG_EXAMPLE_BUTTONS_NAME4="UP" -CONFIG_EXAMPLE_BUTTONS_NAME5="DOWN" -CONFIG_EXAMPLE_BUTTONS_NAME6="LEFT" -CONFIG_EXAMPLE_BUTTONS_NAME7="RIGHT" +CONFIG_EXAMPLES_BUTTONS_MIN=0 +CONFIG_EXAMPLES_BUTTONS_MAX=7 +CONFIG_EXAMPLES_IRQBUTTONS_MIN=0 +CONFIG_EXAMPLES_IRQBUTTONS_MAX=7 +CONFIG_EXAMPLES_BUTTONS_NAME0="BUT1" +CONFIG_EXAMPLES_BUTTONS_NAME1="BUT2" +CONFIG_EXAMPLES_BUTTONS_NAME2="WAKE-UP" +CONFIG_EXAMPLES_BUTTONS_NAME3="CENTER" +CONFIG_EXAMPLES_BUTTONS_NAME4="UP" +CONFIG_EXAMPLES_BUTTONS_NAME5="DOWN" +CONFIG_EXAMPLES_BUTTONS_NAME6="LEFT" +CONFIG_EXAMPLES_BUTTONS_NAME7="RIGHT" # # Settings for apps/nshlib diff --git a/nuttx/configs/olimex-lpc1766stk/hidkbd/defconfig b/nuttx/configs/olimex-lpc1766stk/hidkbd/defconfig index 9acf60d9d..7c9fe4c4e 100755 --- a/nuttx/configs/olimex-lpc1766stk/hidkbd/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/hidkbd/defconfig @@ -397,21 +397,21 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest @@ -423,18 +423,18 @@ CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=3 # # Settings for examples/buttons # -CONFIG_EXAMPLE_BUTTONS_MIN=0 -CONFIG_EXAMPLE_BUTTONS_MAX=7 -CONFIG_EXAMPLE_IRQBUTTONS_MIN=0 -CONFIG_EXAMPLE_IRQBUTTONS_MAX=7 -CONFIG_EXAMPLE_BUTTONS_NAME0="BUT1" -CONFIG_EXAMPLE_BUTTONS_NAME1="BUT2" -CONFIG_EXAMPLE_BUTTONS_NAME2="WAKE-UP" -CONFIG_EXAMPLE_BUTTONS_NAME3="CENTER" -CONFIG_EXAMPLE_BUTTONS_NAME4="UP" -CONFIG_EXAMPLE_BUTTONS_NAME5="DOWN" -CONFIG_EXAMPLE_BUTTONS_NAME6="LEFT" -CONFIG_EXAMPLE_BUTTONS_NAME7="RIGHT" +CONFIG_EXAMPLES_BUTTONS_MIN=0 +CONFIG_EXAMPLES_BUTTONS_MAX=7 +CONFIG_EXAMPLES_IRQBUTTONS_MIN=0 +CONFIG_EXAMPLES_IRQBUTTONS_MAX=7 +CONFIG_EXAMPLES_BUTTONS_NAME0="BUT1" +CONFIG_EXAMPLES_BUTTONS_NAME1="BUT2" +CONFIG_EXAMPLES_BUTTONS_NAME2="WAKE-UP" +CONFIG_EXAMPLES_BUTTONS_NAME3="CENTER" +CONFIG_EXAMPLES_BUTTONS_NAME4="UP" +CONFIG_EXAMPLES_BUTTONS_NAME5="DOWN" +CONFIG_EXAMPLES_BUTTONS_NAME6="LEFT" +CONFIG_EXAMPLES_BUTTONS_NAME7="RIGHT" # # Settings for apps/nshlib diff --git a/nuttx/configs/olimex-lpc1766stk/nettest/defconfig b/nuttx/configs/olimex-lpc1766stk/nettest/defconfig index 040b3ecff..628ff0112 100755 --- a/nuttx/configs/olimex-lpc1766stk/nettest/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/nettest/defconfig @@ -376,21 +376,21 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest @@ -402,18 +402,18 @@ CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=3 # # Settings for examples/buttons # -CONFIG_EXAMPLE_BUTTONS_MIN=0 -CONFIG_EXAMPLE_BUTTONS_MAX=7 -CONFIG_EXAMPLE_IRQBUTTONS_MIN=0 -CONFIG_EXAMPLE_IRQBUTTONS_MAX=7 -CONFIG_EXAMPLE_BUTTONS_NAME0="BUT1" -CONFIG_EXAMPLE_BUTTONS_NAME1="BUT2" -CONFIG_EXAMPLE_BUTTONS_NAME2="WAKE-UP" -CONFIG_EXAMPLE_BUTTONS_NAME3="CENTER" -CONFIG_EXAMPLE_BUTTONS_NAME4="UP" -CONFIG_EXAMPLE_BUTTONS_NAME5="DOWN" -CONFIG_EXAMPLE_BUTTONS_NAME6="LEFT" -CONFIG_EXAMPLE_BUTTONS_NAME7="RIGHT" +CONFIG_EXAMPLES_BUTTONS_MIN=0 +CONFIG_EXAMPLES_BUTTONS_MAX=7 +CONFIG_EXAMPLES_IRQBUTTONS_MIN=0 +CONFIG_EXAMPLES_IRQBUTTONS_MAX=7 +CONFIG_EXAMPLES_BUTTONS_NAME0="BUT1" +CONFIG_EXAMPLES_BUTTONS_NAME1="BUT2" +CONFIG_EXAMPLES_BUTTONS_NAME2="WAKE-UP" +CONFIG_EXAMPLES_BUTTONS_NAME3="CENTER" +CONFIG_EXAMPLES_BUTTONS_NAME4="UP" +CONFIG_EXAMPLES_BUTTONS_NAME5="DOWN" +CONFIG_EXAMPLES_BUTTONS_NAME6="LEFT" +CONFIG_EXAMPLES_BUTTONS_NAME7="RIGHT" # # Settings for apps/nshlib diff --git a/nuttx/configs/olimex-lpc1766stk/nsh/defconfig b/nuttx/configs/olimex-lpc1766stk/nsh/defconfig index 1324ca5d4..c2722cb9b 100755 --- a/nuttx/configs/olimex-lpc1766stk/nsh/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/nsh/defconfig @@ -420,21 +420,21 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest @@ -446,18 +446,18 @@ CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=3 # # Settings for examples/buttons # -CONFIG_EXAMPLE_BUTTONS_MIN=0 -CONFIG_EXAMPLE_BUTTONS_MAX=7 -CONFIG_EXAMPLE_IRQBUTTONS_MIN=0 -CONFIG_EXAMPLE_IRQBUTTONS_MAX=7 -CONFIG_EXAMPLE_BUTTONS_NAME0="BUT1" -CONFIG_EXAMPLE_BUTTONS_NAME1="BUT2" -CONFIG_EXAMPLE_BUTTONS_NAME2="WAKE-UP" -CONFIG_EXAMPLE_BUTTONS_NAME3="CENTER" -CONFIG_EXAMPLE_BUTTONS_NAME4="UP" -CONFIG_EXAMPLE_BUTTONS_NAME5="DOWN" -CONFIG_EXAMPLE_BUTTONS_NAME6="LEFT" -CONFIG_EXAMPLE_BUTTONS_NAME7="RIGHT" +CONFIG_EXAMPLES_BUTTONS_MIN=0 +CONFIG_EXAMPLES_BUTTONS_MAX=7 +CONFIG_EXAMPLES_IRQBUTTONS_MIN=0 +CONFIG_EXAMPLES_IRQBUTTONS_MAX=7 +CONFIG_EXAMPLES_BUTTONS_NAME0="BUT1" +CONFIG_EXAMPLES_BUTTONS_NAME1="BUT2" +CONFIG_EXAMPLES_BUTTONS_NAME2="WAKE-UP" +CONFIG_EXAMPLES_BUTTONS_NAME3="CENTER" +CONFIG_EXAMPLES_BUTTONS_NAME4="UP" +CONFIG_EXAMPLES_BUTTONS_NAME5="DOWN" +CONFIG_EXAMPLES_BUTTONS_NAME6="LEFT" +CONFIG_EXAMPLES_BUTTONS_NAME7="RIGHT" # # Settings for apps/nshlib diff --git a/nuttx/configs/olimex-lpc1766stk/nx/defconfig b/nuttx/configs/olimex-lpc1766stk/nx/defconfig index de5763c0e..d86b8b83f 100755 --- a/nuttx/configs/olimex-lpc1766stk/nx/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/nx/defconfig @@ -441,21 +441,21 @@ CONFIG_LCD_MAXPOWER=127 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest @@ -467,18 +467,18 @@ CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=3 # # Settings for examples/buttons # -CONFIG_EXAMPLE_BUTTONS_MIN=0 -CONFIG_EXAMPLE_BUTTONS_MAX=7 -CONFIG_EXAMPLE_IRQBUTTONS_MIN=0 -CONFIG_EXAMPLE_IRQBUTTONS_MAX=7 -CONFIG_EXAMPLE_BUTTONS_NAME0="BUT1" -CONFIG_EXAMPLE_BUTTONS_NAME1="BUT2" -CONFIG_EXAMPLE_BUTTONS_NAME2="WAKE-UP" -CONFIG_EXAMPLE_BUTTONS_NAME3="CENTER" -CONFIG_EXAMPLE_BUTTONS_NAME4="UP" -CONFIG_EXAMPLE_BUTTONS_NAME5="DOWN" -CONFIG_EXAMPLE_BUTTONS_NAME6="LEFT" -CONFIG_EXAMPLE_BUTTONS_NAME7="RIGHT" +CONFIG_EXAMPLES_BUTTONS_MIN=0 +CONFIG_EXAMPLES_BUTTONS_MAX=7 +CONFIG_EXAMPLES_IRQBUTTONS_MIN=0 +CONFIG_EXAMPLES_IRQBUTTONS_MAX=7 +CONFIG_EXAMPLES_BUTTONS_NAME0="BUT1" +CONFIG_EXAMPLES_BUTTONS_NAME1="BUT2" +CONFIG_EXAMPLES_BUTTONS_NAME2="WAKE-UP" +CONFIG_EXAMPLES_BUTTONS_NAME3="CENTER" +CONFIG_EXAMPLES_BUTTONS_NAME4="UP" +CONFIG_EXAMPLES_BUTTONS_NAME5="DOWN" +CONFIG_EXAMPLES_BUTTONS_NAME6="LEFT" +CONFIG_EXAMPLES_BUTTONS_NAME7="RIGHT" # # Settings for apps/nshlib diff --git a/nuttx/configs/olimex-lpc1766stk/ostest/defconfig b/nuttx/configs/olimex-lpc1766stk/ostest/defconfig index f36f911e6..a11c02276 100755 --- a/nuttx/configs/olimex-lpc1766stk/ostest/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/ostest/defconfig @@ -369,21 +369,21 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest @@ -395,18 +395,18 @@ CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=3 # # Settings for examples/buttons # -CONFIG_EXAMPLE_BUTTONS_MIN=0 -CONFIG_EXAMPLE_BUTTONS_MAX=7 -CONFIG_EXAMPLE_IRQBUTTONS_MIN=0 -CONFIG_EXAMPLE_IRQBUTTONS_MAX=7 -CONFIG_EXAMPLE_BUTTONS_NAME0="BUT1" -CONFIG_EXAMPLE_BUTTONS_NAME1="BUT2" -CONFIG_EXAMPLE_BUTTONS_NAME2="WAKE-UP" -CONFIG_EXAMPLE_BUTTONS_NAME3="CENTER" -CONFIG_EXAMPLE_BUTTONS_NAME4="UP" -CONFIG_EXAMPLE_BUTTONS_NAME5="DOWN" -CONFIG_EXAMPLE_BUTTONS_NAME6="LEFT" -CONFIG_EXAMPLE_BUTTONS_NAME7="RIGHT" +CONFIG_EXAMPLES_BUTTONS_MIN=0 +CONFIG_EXAMPLES_BUTTONS_MAX=7 +CONFIG_EXAMPLES_IRQBUTTONS_MIN=0 +CONFIG_EXAMPLES_IRQBUTTONS_MAX=7 +CONFIG_EXAMPLES_BUTTONS_NAME0="BUT1" +CONFIG_EXAMPLES_BUTTONS_NAME1="BUT2" +CONFIG_EXAMPLES_BUTTONS_NAME2="WAKE-UP" +CONFIG_EXAMPLES_BUTTONS_NAME3="CENTER" +CONFIG_EXAMPLES_BUTTONS_NAME4="UP" +CONFIG_EXAMPLES_BUTTONS_NAME5="DOWN" +CONFIG_EXAMPLES_BUTTONS_NAME6="LEFT" +CONFIG_EXAMPLES_BUTTONS_NAME7="RIGHT" # # Settings for apps/nshlib diff --git a/nuttx/configs/olimex-lpc1766stk/slip-httpd/defconfig b/nuttx/configs/olimex-lpc1766stk/slip-httpd/defconfig index a30c2b9a6..32092d216 100755 --- a/nuttx/configs/olimex-lpc1766stk/slip-httpd/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/slip-httpd/defconfig @@ -412,28 +412,28 @@ CONFIG_THTTPD_URLPATTERN=n # # Additional settings for examples/thttpd # -CONFIG_EXAMPLE_THTTPD_NOMAC=y -CONFIG_EXAMPLE_THTTPD_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_THTTPD_NETMASK=0xffffff00 +CONFIG_EXAMPLES_THTTPD_NOMAC=y +CONFIG_EXAMPLES_THTTPD_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_THTTPD_NETMASK=0xffffff00 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest @@ -445,18 +445,18 @@ CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=3 # # Settings for examples/buttons # -CONFIG_EXAMPLE_BUTTONS_MIN=0 -CONFIG_EXAMPLE_BUTTONS_MAX=7 -CONFIG_EXAMPLE_IRQBUTTONS_MIN=0 -CONFIG_EXAMPLE_IRQBUTTONS_MAX=7 -CONFIG_EXAMPLE_BUTTONS_NAME0="BUT1" -CONFIG_EXAMPLE_BUTTONS_NAME1="BUT2" -CONFIG_EXAMPLE_BUTTONS_NAME2="WAKE-UP" -CONFIG_EXAMPLE_BUTTONS_NAME3="CENTER" -CONFIG_EXAMPLE_BUTTONS_NAME4="UP" -CONFIG_EXAMPLE_BUTTONS_NAME5="DOWN" -CONFIG_EXAMPLE_BUTTONS_NAME6="LEFT" -CONFIG_EXAMPLE_BUTTONS_NAME7="RIGHT" +CONFIG_EXAMPLES_BUTTONS_MIN=0 +CONFIG_EXAMPLES_BUTTONS_MAX=7 +CONFIG_EXAMPLES_IRQBUTTONS_MIN=0 +CONFIG_EXAMPLES_IRQBUTTONS_MAX=7 +CONFIG_EXAMPLES_BUTTONS_NAME0="BUT1" +CONFIG_EXAMPLES_BUTTONS_NAME1="BUT2" +CONFIG_EXAMPLES_BUTTONS_NAME2="WAKE-UP" +CONFIG_EXAMPLES_BUTTONS_NAME3="CENTER" +CONFIG_EXAMPLES_BUTTONS_NAME4="UP" +CONFIG_EXAMPLES_BUTTONS_NAME5="DOWN" +CONFIG_EXAMPLES_BUTTONS_NAME6="LEFT" +CONFIG_EXAMPLES_BUTTONS_NAME7="RIGHT" # # Settings for apps/nshlib diff --git a/nuttx/configs/olimex-lpc1766stk/thttpd/defconfig b/nuttx/configs/olimex-lpc1766stk/thttpd/defconfig index 1c287cfca..94ac19f42 100755 --- a/nuttx/configs/olimex-lpc1766stk/thttpd/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/thttpd/defconfig @@ -407,28 +407,28 @@ CONFIG_THTTPD_URLPATTERN=n # # Additional settings for examples/thttpd # -CONFIG_EXAMPLE_THTTPD_NOMAC=y -CONFIG_EXAMPLE_THTTPD_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_THTTPD_NETMASK=0xffffff00 +CONFIG_EXAMPLES_THTTPD_NOMAC=y +CONFIG_EXAMPLES_THTTPD_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_THTTPD_NETMASK=0xffffff00 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest @@ -440,18 +440,18 @@ CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=3 # # Settings for examples/buttons # -CONFIG_EXAMPLE_BUTTONS_MIN=0 -CONFIG_EXAMPLE_BUTTONS_MAX=7 -CONFIG_EXAMPLE_IRQBUTTONS_MIN=0 -CONFIG_EXAMPLE_IRQBUTTONS_MAX=7 -CONFIG_EXAMPLE_BUTTONS_NAME0="BUT1" -CONFIG_EXAMPLE_BUTTONS_NAME1="BUT2" -CONFIG_EXAMPLE_BUTTONS_NAME2="WAKE-UP" -CONFIG_EXAMPLE_BUTTONS_NAME3="CENTER" -CONFIG_EXAMPLE_BUTTONS_NAME4="UP" -CONFIG_EXAMPLE_BUTTONS_NAME5="DOWN" -CONFIG_EXAMPLE_BUTTONS_NAME6="LEFT" -CONFIG_EXAMPLE_BUTTONS_NAME7="RIGHT" +CONFIG_EXAMPLES_BUTTONS_MIN=0 +CONFIG_EXAMPLES_BUTTONS_MAX=7 +CONFIG_EXAMPLES_IRQBUTTONS_MIN=0 +CONFIG_EXAMPLES_IRQBUTTONS_MAX=7 +CONFIG_EXAMPLES_BUTTONS_NAME0="BUT1" +CONFIG_EXAMPLES_BUTTONS_NAME1="BUT2" +CONFIG_EXAMPLES_BUTTONS_NAME2="WAKE-UP" +CONFIG_EXAMPLES_BUTTONS_NAME3="CENTER" +CONFIG_EXAMPLES_BUTTONS_NAME4="UP" +CONFIG_EXAMPLES_BUTTONS_NAME5="DOWN" +CONFIG_EXAMPLES_BUTTONS_NAME6="LEFT" +CONFIG_EXAMPLES_BUTTONS_NAME7="RIGHT" # # Settings for apps/nshlib diff --git a/nuttx/configs/olimex-lpc1766stk/usbserial/defconfig b/nuttx/configs/olimex-lpc1766stk/usbserial/defconfig index 4ead7ffeb..2bd892cc3 100755 --- a/nuttx/configs/olimex-lpc1766stk/usbserial/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/usbserial/defconfig @@ -370,21 +370,21 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest @@ -396,18 +396,18 @@ CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=3 # # Settings for examples/buttons # -CONFIG_EXAMPLE_BUTTONS_MIN=0 -CONFIG_EXAMPLE_BUTTONS_MAX=7 -CONFIG_EXAMPLE_IRQBUTTONS_MIN=0 -CONFIG_EXAMPLE_IRQBUTTONS_MAX=7 -CONFIG_EXAMPLE_BUTTONS_NAME0="BUT1" -CONFIG_EXAMPLE_BUTTONS_NAME1="BUT2" -CONFIG_EXAMPLE_BUTTONS_NAME2="WAKE-UP" -CONFIG_EXAMPLE_BUTTONS_NAME3="CENTER" -CONFIG_EXAMPLE_BUTTONS_NAME4="UP" -CONFIG_EXAMPLE_BUTTONS_NAME5="DOWN" -CONFIG_EXAMPLE_BUTTONS_NAME6="LEFT" -CONFIG_EXAMPLE_BUTTONS_NAME7="RIGHT" +CONFIG_EXAMPLES_BUTTONS_MIN=0 +CONFIG_EXAMPLES_BUTTONS_MAX=7 +CONFIG_EXAMPLES_IRQBUTTONS_MIN=0 +CONFIG_EXAMPLES_IRQBUTTONS_MAX=7 +CONFIG_EXAMPLES_BUTTONS_NAME0="BUT1" +CONFIG_EXAMPLES_BUTTONS_NAME1="BUT2" +CONFIG_EXAMPLES_BUTTONS_NAME2="WAKE-UP" +CONFIG_EXAMPLES_BUTTONS_NAME3="CENTER" +CONFIG_EXAMPLES_BUTTONS_NAME4="UP" +CONFIG_EXAMPLES_BUTTONS_NAME5="DOWN" +CONFIG_EXAMPLES_BUTTONS_NAME6="LEFT" +CONFIG_EXAMPLES_BUTTONS_NAME7="RIGHT" # # Settings for apps/nshlib diff --git a/nuttx/configs/olimex-lpc1766stk/usbstorage/defconfig b/nuttx/configs/olimex-lpc1766stk/usbstorage/defconfig index 53cf8001c..8b55cc94d 100755 --- a/nuttx/configs/olimex-lpc1766stk/usbstorage/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/usbstorage/defconfig @@ -371,21 +371,21 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest @@ -397,18 +397,18 @@ CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=3 # # Settings for examples/buttons # -CONFIG_EXAMPLE_BUTTONS_MIN=0 -CONFIG_EXAMPLE_BUTTONS_MAX=7 -CONFIG_EXAMPLE_IRQBUTTONS_MIN=0 -CONFIG_EXAMPLE_IRQBUTTONS_MAX=7 -CONFIG_EXAMPLE_BUTTONS_NAME0="BUT1" -CONFIG_EXAMPLE_BUTTONS_NAME1="BUT2" -CONFIG_EXAMPLE_BUTTONS_NAME2="WAKE-UP" -CONFIG_EXAMPLE_BUTTONS_NAME3="CENTER" -CONFIG_EXAMPLE_BUTTONS_NAME4="UP" -CONFIG_EXAMPLE_BUTTONS_NAME5="DOWN" -CONFIG_EXAMPLE_BUTTONS_NAME6="LEFT" -CONFIG_EXAMPLE_BUTTONS_NAME7="RIGHT" +CONFIG_EXAMPLES_BUTTONS_MIN=0 +CONFIG_EXAMPLES_BUTTONS_MAX=7 +CONFIG_EXAMPLES_IRQBUTTONS_MIN=0 +CONFIG_EXAMPLES_IRQBUTTONS_MAX=7 +CONFIG_EXAMPLES_BUTTONS_NAME0="BUT1" +CONFIG_EXAMPLES_BUTTONS_NAME1="BUT2" +CONFIG_EXAMPLES_BUTTONS_NAME2="WAKE-UP" +CONFIG_EXAMPLES_BUTTONS_NAME3="CENTER" +CONFIG_EXAMPLES_BUTTONS_NAME4="UP" +CONFIG_EXAMPLES_BUTTONS_NAME5="DOWN" +CONFIG_EXAMPLES_BUTTONS_NAME6="LEFT" +CONFIG_EXAMPLES_BUTTONS_NAME7="RIGHT" # # Settings for apps/nshlib diff --git a/nuttx/configs/olimex-lpc1766stk/wlan/defconfig b/nuttx/configs/olimex-lpc1766stk/wlan/defconfig index 0df5f2cf7..4d73807e0 100755 --- a/nuttx/configs/olimex-lpc1766stk/wlan/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/wlan/defconfig @@ -390,30 +390,30 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for apps/examples/wlan # -CONFIG_EXAMPLE_WLAN_DHCPC=n -CONFIG_EXAMPLE_WLAN_NOMAC=n -CONFIG_EXAMPLE_WLAN_IPADDR=0xc0a800c9 -CONFIG_EXAMPLE_WLAN_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_WLAN_NETMASK=0xffffff00 +CONFIG_EXAMPLES_WLAN_DHCPC=n +CONFIG_EXAMPLES_WLAN_NOMAC=n +CONFIG_EXAMPLES_WLAN_IPADDR=0xc0a800c9 +CONFIG_EXAMPLES_WLAN_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_WLAN_NETMASK=0xffffff00 # # Settings for examples/ostest diff --git a/nuttx/configs/olimex-stm32-p107/nsh/defconfig b/nuttx/configs/olimex-stm32-p107/nsh/defconfig index e3fb69ca2..67a153f9a 100644 --- a/nuttx/configs/olimex-stm32-p107/nsh/defconfig +++ b/nuttx/configs/olimex-stm32-p107/nsh/defconfig @@ -443,20 +443,20 @@ CONFIG_WATCHDOG=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/olimex-stm32-p107/ostest/defconfig b/nuttx/configs/olimex-stm32-p107/ostest/defconfig index 36fade11b..26a8470d2 100644 --- a/nuttx/configs/olimex-stm32-p107/ostest/defconfig +++ b/nuttx/configs/olimex-stm32-p107/ostest/defconfig @@ -420,20 +420,20 @@ CONFIG_WATCHDOG=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/olimex-strp711/nettest/defconfig b/nuttx/configs/olimex-strp711/nettest/defconfig index e8455ab94..c401fe8c6 100755 --- a/nuttx/configs/olimex-strp711/nettest/defconfig +++ b/nuttx/configs/olimex-strp711/nettest/defconfig @@ -338,13 +338,13 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/pcblogic-pic32mx/nsh/defconfig b/nuttx/configs/pcblogic-pic32mx/nsh/defconfig index 09febe7b1..1e439e466 100644 --- a/nuttx/configs/pcblogic-pic32mx/nsh/defconfig +++ b/nuttx/configs/pcblogic-pic32mx/nsh/defconfig @@ -373,21 +373,21 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/pcblogic-pic32mx/ostest/defconfig b/nuttx/configs/pcblogic-pic32mx/ostest/defconfig index dc76a54bb..868ba4669 100644 --- a/nuttx/configs/pcblogic-pic32mx/ostest/defconfig +++ b/nuttx/configs/pcblogic-pic32mx/ostest/defconfig @@ -363,21 +363,21 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/pic32-starterkit/nsh/defconfig b/nuttx/configs/pic32-starterkit/nsh/defconfig index 5c19d2e43..17cb151a7 100644 --- a/nuttx/configs/pic32-starterkit/nsh/defconfig +++ b/nuttx/configs/pic32-starterkit/nsh/defconfig @@ -537,21 +537,21 @@ CONFIG_NX_MXCLIENTMSGS=16 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/pic32-starterkit/nsh2/defconfig b/nuttx/configs/pic32-starterkit/nsh2/defconfig index 8d9bd8e27..c751591b2 100644 --- a/nuttx/configs/pic32-starterkit/nsh2/defconfig +++ b/nuttx/configs/pic32-starterkit/nsh2/defconfig @@ -536,21 +536,21 @@ CONFIG_NX_MXCLIENTMSGS=16 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/pic32-starterkit/ostest/defconfig b/nuttx/configs/pic32-starterkit/ostest/defconfig index 687b63970..c8e32419e 100644 --- a/nuttx/configs/pic32-starterkit/ostest/defconfig +++ b/nuttx/configs/pic32-starterkit/ostest/defconfig @@ -534,21 +534,21 @@ CONFIG_NX_MXCLIENTMSGS=16 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/pic32mx7mmb/nsh/defconfig b/nuttx/configs/pic32mx7mmb/nsh/defconfig index bb9531694..052363656 100644 --- a/nuttx/configs/pic32mx7mmb/nsh/defconfig +++ b/nuttx/configs/pic32mx7mmb/nsh/defconfig @@ -583,21 +583,21 @@ CONFIG_LCD_RPORTRAIT=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/pic32mx7mmb/ostest/defconfig b/nuttx/configs/pic32mx7mmb/ostest/defconfig index a14fa9948..851f6022f 100644 --- a/nuttx/configs/pic32mx7mmb/ostest/defconfig +++ b/nuttx/configs/pic32mx7mmb/ostest/defconfig @@ -534,21 +534,21 @@ CONFIG_NX_MXCLIENTMSGS=16 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/qemu-i486/nsh/defconfig b/nuttx/configs/qemu-i486/nsh/defconfig index 72e97539a..9085eb5fa 100644 --- a/nuttx/configs/qemu-i486/nsh/defconfig +++ b/nuttx/configs/qemu-i486/nsh/defconfig @@ -250,20 +250,20 @@ CONFIG_NET_RESOLV_ENTRIES=4 # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_UIP_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_UIP_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0xc0a8006a +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0xc0a8006a # # Settings for examples/ostest diff --git a/nuttx/configs/qemu-i486/ostest/defconfig b/nuttx/configs/qemu-i486/ostest/defconfig index 3f87e11cd..a9867fdc9 100644 --- a/nuttx/configs/qemu-i486/ostest/defconfig +++ b/nuttx/configs/qemu-i486/ostest/defconfig @@ -182,20 +182,20 @@ CONFIG_NET_RESOLV_ENTRIES=4 # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_UIP_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_UIP_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0xc0a8006a +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0xc0a8006a # # Settings for examples/ostest diff --git a/nuttx/configs/rgmp/arm/default/defconfig b/nuttx/configs/rgmp/arm/default/defconfig index d722dd5e7..186c68724 100644 --- a/nuttx/configs/rgmp/arm/default/defconfig +++ b/nuttx/configs/rgmp/arm/default/defconfig @@ -181,20 +181,20 @@ CONFIG_NET_RESOLV_ENTRIES=4 # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_IPADDR=0xc0a80a02 -CONFIG_EXAMPLE_UIP_DRIPADDR=0xc0a80a01 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0xc0a80a02 +CONFIG_EXAMPLES_UIP_DRIPADDR=0xc0a80a01 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0xc0a8006a +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0xc0a8006a # # Settings for examples/nsh diff --git a/nuttx/configs/rgmp/arm/nsh/defconfig b/nuttx/configs/rgmp/arm/nsh/defconfig index 279437d47..8fbbc7b8b 100644 --- a/nuttx/configs/rgmp/arm/nsh/defconfig +++ b/nuttx/configs/rgmp/arm/nsh/defconfig @@ -181,20 +181,20 @@ CONFIG_NET_RESOLV_ENTRIES=4 # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_UIP_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_UIP_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0xc0a8006a +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0xc0a8006a # # Settings for apps/nshlib diff --git a/nuttx/configs/rgmp/x86/default/defconfig b/nuttx/configs/rgmp/x86/default/defconfig index 4e37d9092..9b4b58d89 100644 --- a/nuttx/configs/rgmp/x86/default/defconfig +++ b/nuttx/configs/rgmp/x86/default/defconfig @@ -181,20 +181,20 @@ CONFIG_NET_RESOLV_ENTRIES=4 # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_IPADDR=0xc0a80a02 -CONFIG_EXAMPLE_UIP_DRIPADDR=0xc0a80a01 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0xc0a80a02 +CONFIG_EXAMPLES_UIP_DRIPADDR=0xc0a80a01 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0xc0a8006a +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0xc0a8006a # # Settings for examples/nsh diff --git a/nuttx/configs/rgmp/x86/nsh/defconfig b/nuttx/configs/rgmp/x86/nsh/defconfig index 363ef609d..7af320ff7 100644 --- a/nuttx/configs/rgmp/x86/nsh/defconfig +++ b/nuttx/configs/rgmp/x86/nsh/defconfig @@ -181,20 +181,20 @@ CONFIG_NET_RESOLV_ENTRIES=4 # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_UIP_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_UIP_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0xc0a8006a +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0xc0a8006a # # Settings for apps/nshlib diff --git a/nuttx/configs/sam3u-ek/knsh/defconfig b/nuttx/configs/sam3u-ek/knsh/defconfig index 82616f338..9aba512ed 100755 --- a/nuttx/configs/sam3u-ek/knsh/defconfig +++ b/nuttx/configs/sam3u-ek/knsh/defconfig @@ -395,20 +395,20 @@ CONFIG_NX_MXCLIENTMSGS=16 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/sam3u-ek/nsh/defconfig b/nuttx/configs/sam3u-ek/nsh/defconfig index 56071d223..02b980418 100755 --- a/nuttx/configs/sam3u-ek/nsh/defconfig +++ b/nuttx/configs/sam3u-ek/nsh/defconfig @@ -370,20 +370,20 @@ CONFIG_NX_MXCLIENTMSGS=16 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/sam3u-ek/nx/defconfig b/nuttx/configs/sam3u-ek/nx/defconfig index 943c47cfc..82e9e3cbc 100755 --- a/nuttx/configs/sam3u-ek/nx/defconfig +++ b/nuttx/configs/sam3u-ek/nx/defconfig @@ -379,20 +379,20 @@ CONFIG_NX_MXCLIENTMSGS=16 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/sam3u-ek/ostest/defconfig b/nuttx/configs/sam3u-ek/ostest/defconfig index 098fc3600..da582acb6 100755 --- a/nuttx/configs/sam3u-ek/ostest/defconfig +++ b/nuttx/configs/sam3u-ek/ostest/defconfig @@ -370,20 +370,20 @@ CONFIG_NX_MXCLIENTMSGS=16 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/sam3u-ek/touchscreen/defconfig b/nuttx/configs/sam3u-ek/touchscreen/defconfig index 2165dec4b..f3ced72cc 100755 --- a/nuttx/configs/sam3u-ek/touchscreen/defconfig +++ b/nuttx/configs/sam3u-ek/touchscreen/defconfig @@ -410,20 +410,20 @@ CONFIG_LCD_PORTRAIT=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/shenzhou/nsh/defconfig b/nuttx/configs/shenzhou/nsh/defconfig index 21b7fcf90..fdc065c48 100644 --- a/nuttx/configs/shenzhou/nsh/defconfig +++ b/nuttx/configs/shenzhou/nsh/defconfig @@ -694,7 +694,7 @@ CONFIG_EXAMPLES_NSH=y # # UDP Discovery Daemon Example # -# CONFIG_EXAMPLE_DISCOVER is not set +# CONFIG_EXAMPLES_DISCOVER is not set # # uIP Web Server Example diff --git a/nuttx/configs/shenzhou/nxwm/defconfig b/nuttx/configs/shenzhou/nxwm/defconfig index 0bdc9f45c..e4316d1fe 100644 --- a/nuttx/configs/shenzhou/nxwm/defconfig +++ b/nuttx/configs/shenzhou/nxwm/defconfig @@ -794,7 +794,7 @@ CONFIG_NAMEDAPP=y # # UDP Discovery Daemon Example # -# CONFIG_EXAMPLE_DISCOVER is not set +# CONFIG_EXAMPLES_DISCOVER is not set # # uIP Web Server Example diff --git a/nuttx/configs/sim/README.txt b/nuttx/configs/sim/README.txt index b8a921e7f..ee262e49a 100644 --- a/nuttx/configs/sim/README.txt +++ b/nuttx/configs/sim/README.txt @@ -221,7 +221,7 @@ nettest NOTE that the IP address is hard-coded in arch/sim/src/up_wpcap.c. You will either need to edit your configuration files to use 10.0.0.1 - on the "target" (CONFIG_EXAMPLE_NETTEST_*) or edit up_wpcap.c to + on the "target" (CONFIG_EXAMPLES_NETTEST_*) or edit up_wpcap.c to select the IP address that you want to use. nsh diff --git a/nuttx/configs/sim/mount/defconfig b/nuttx/configs/sim/mount/defconfig index f5d28054f..b980b38dd 100644 --- a/nuttx/configs/sim/mount/defconfig +++ b/nuttx/configs/sim/mount/defconfig @@ -173,20 +173,20 @@ CONFIG_NET_RESOLV_ENTRIES=4 # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_UIP_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_UIP_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0xc0a8006a +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0xc0a8006a # # Settings for examples/ostest diff --git a/nuttx/configs/sim/nettest/defconfig b/nuttx/configs/sim/nettest/defconfig index 83de44c36..d72404640 100644 --- a/nuttx/configs/sim/nettest/defconfig +++ b/nuttx/configs/sim/nettest/defconfig @@ -173,20 +173,20 @@ CONFIG_NET_RESOLV_ENTRIES=4 # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_UIP_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_UIP_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0xc0a8006a +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0xc0a8006a # # Settings for examples/ostest diff --git a/nuttx/configs/sim/nsh/defconfig b/nuttx/configs/sim/nsh/defconfig index 3f0ceab26..cd1fc8c7b 100644 --- a/nuttx/configs/sim/nsh/defconfig +++ b/nuttx/configs/sim/nsh/defconfig @@ -202,20 +202,20 @@ CONFIG_NET_RESOLV_ENTRIES=4 # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_UIP_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_UIP_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0xc0a8006a +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0xc0a8006a # # Settings for examples/ostest diff --git a/nuttx/configs/sim/nsh2/defconfig b/nuttx/configs/sim/nsh2/defconfig index f6f36bf51..787e388c7 100644 --- a/nuttx/configs/sim/nsh2/defconfig +++ b/nuttx/configs/sim/nsh2/defconfig @@ -250,21 +250,21 @@ CONFIG_NX_MXCLIENTMSGS=16 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_UIP_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_UIP_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0xc0a8006a +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0xc0a8006a # # Settings for examples/ostest diff --git a/nuttx/configs/sim/nx/defconfig b/nuttx/configs/sim/nx/defconfig index 34d86f384..5b48d72a7 100644 --- a/nuttx/configs/sim/nx/defconfig +++ b/nuttx/configs/sim/nx/defconfig @@ -228,21 +228,21 @@ CONFIG_NXCONSOLE_MXCHARS=256 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_UIP_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_UIP_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0xc0a8006a +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0xc0a8006a # # Settings for examples/ostest diff --git a/nuttx/configs/sim/nx11/defconfig b/nuttx/configs/sim/nx11/defconfig index 8734ebc69..43d57bd50 100644 --- a/nuttx/configs/sim/nx11/defconfig +++ b/nuttx/configs/sim/nx11/defconfig @@ -235,21 +235,21 @@ CONFIG_NXCONSOLE_MXCHARS=256 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_UIP_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_UIP_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0xc0a8006a +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0xc0a8006a # # Settings for examples/ostest diff --git a/nuttx/configs/sim/nxffs/defconfig b/nuttx/configs/sim/nxffs/defconfig index 22746a2f6..c30227bd8 100644 --- a/nuttx/configs/sim/nxffs/defconfig +++ b/nuttx/configs/sim/nxffs/defconfig @@ -174,20 +174,20 @@ CONFIG_NET_RESOLV_ENTRIES=4 # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_UIP_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_UIP_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0xc0a8006a +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0xc0a8006a # # Settings for examples/ostest diff --git a/nuttx/configs/sim/nxwm/defconfig b/nuttx/configs/sim/nxwm/defconfig index 812233cbf..d34202e05 100644 --- a/nuttx/configs/sim/nxwm/defconfig +++ b/nuttx/configs/sim/nxwm/defconfig @@ -283,21 +283,21 @@ CONFIG_NXCONSOLE_MXCHARS=256 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_UIP_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_UIP_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0xc0a8006a +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0xc0a8006a # # Settings for examples/ostest diff --git a/nuttx/configs/sim/ostest/defconfig b/nuttx/configs/sim/ostest/defconfig index 92c696dc6..0d3669a25 100644 --- a/nuttx/configs/sim/ostest/defconfig +++ b/nuttx/configs/sim/ostest/defconfig @@ -173,20 +173,20 @@ CONFIG_NET_RESOLV_ENTRIES=4 # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_UIP_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_UIP_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0xc0a8006a +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0xc0a8006a # # Settings for examples/ostest diff --git a/nuttx/configs/sim/pashello/defconfig b/nuttx/configs/sim/pashello/defconfig index 57530d3bb..e3cf3a7b5 100644 --- a/nuttx/configs/sim/pashello/defconfig +++ b/nuttx/configs/sim/pashello/defconfig @@ -173,20 +173,20 @@ CONFIG_NET_RESOLV_ENTRIES=4 # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_UIP_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_UIP_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0xc0a8006a +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0xc0a8006a # # Settings for examples/nsh diff --git a/nuttx/configs/sim/touchscreen/defconfig b/nuttx/configs/sim/touchscreen/defconfig index b9630c8e2..b112449b3 100644 --- a/nuttx/configs/sim/touchscreen/defconfig +++ b/nuttx/configs/sim/touchscreen/defconfig @@ -224,20 +224,20 @@ CONFIG_NX_MXCLIENTMSGS=16 # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_UIP_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_UIP_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0xc0a80080 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0xc0a80001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0xc0a8006a +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0xc0a80080 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0xc0a80001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0xc0a8006a # # Settings for examples/ostest diff --git a/nuttx/configs/skp16c26/ostest/defconfig b/nuttx/configs/skp16c26/ostest/defconfig index 91917f8f0..8cb2eb469 100644 --- a/nuttx/configs/skp16c26/ostest/defconfig +++ b/nuttx/configs/skp16c26/ostest/defconfig @@ -266,20 +266,20 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/nsh diff --git a/nuttx/configs/stm3210e-eval/RIDE/defconfig b/nuttx/configs/stm3210e-eval/RIDE/defconfig index a5b60fe4e..f4593d5ea 100755 --- a/nuttx/configs/stm3210e-eval/RIDE/defconfig +++ b/nuttx/configs/stm3210e-eval/RIDE/defconfig @@ -378,20 +378,20 @@ CONFIG_WATCHDOG=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/stm3210e-eval/buttons/defconfig b/nuttx/configs/stm3210e-eval/buttons/defconfig index fbfac0dc6..ac3f10887 100644 --- a/nuttx/configs/stm3210e-eval/buttons/defconfig +++ b/nuttx/configs/stm3210e-eval/buttons/defconfig @@ -389,36 +389,36 @@ CONFIG_WATCHDOG=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/buttons # -CONFIG_EXAMPLE_BUTTONS_MIN=0 -CONFIG_EXAMPLE_BUTTONS_MAX=7 -CONFIG_EXAMPLE_IRQBUTTONS_MIN=2 -CONFIG_EXAMPLE_IRQBUTTONS_MAX=7 -CONFIG_EXAMPLE_BUTTONS_NAME0="WAKEUP" -CONFIG_EXAMPLE_BUTTONS_NAME1="TAMPER" -CONFIG_EXAMPLE_BUTTONS_NAME2="KEY" -CONFIG_EXAMPLE_BUTTONS_NAME3="SELECT" -CONFIG_EXAMPLE_BUTTONS_NAME4="DOWN" -CONFIG_EXAMPLE_BUTTONS_NAME5="LEFT" -CONFIG_EXAMPLE_BUTTONS_NAME6="RIGHT" -CONFIG_EXAMPLE_BUTTONS_NAME7="UP" +CONFIG_EXAMPLES_BUTTONS_MIN=0 +CONFIG_EXAMPLES_BUTTONS_MAX=7 +CONFIG_EXAMPLES_IRQBUTTONS_MIN=2 +CONFIG_EXAMPLES_IRQBUTTONS_MAX=7 +CONFIG_EXAMPLES_BUTTONS_NAME0="WAKEUP" +CONFIG_EXAMPLES_BUTTONS_NAME1="TAMPER" +CONFIG_EXAMPLES_BUTTONS_NAME2="KEY" +CONFIG_EXAMPLES_BUTTONS_NAME3="SELECT" +CONFIG_EXAMPLES_BUTTONS_NAME4="DOWN" +CONFIG_EXAMPLES_BUTTONS_NAME5="LEFT" +CONFIG_EXAMPLES_BUTTONS_NAME6="RIGHT" +CONFIG_EXAMPLES_BUTTONS_NAME7="UP" # # Settings for examples/ostest diff --git a/nuttx/configs/stm3210e-eval/composite/defconfig b/nuttx/configs/stm3210e-eval/composite/defconfig index 84ed18494..18c2164d3 100755 --- a/nuttx/configs/stm3210e-eval/composite/defconfig +++ b/nuttx/configs/stm3210e-eval/composite/defconfig @@ -438,20 +438,20 @@ CONFIG_COMPOSITE_VERSIONNO=0x0101 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/stm3210e-eval/nsh/defconfig b/nuttx/configs/stm3210e-eval/nsh/defconfig index 27d26ff73..facfe105a 100755 --- a/nuttx/configs/stm3210e-eval/nsh/defconfig +++ b/nuttx/configs/stm3210e-eval/nsh/defconfig @@ -389,20 +389,20 @@ CONFIG_WATCHDOG=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/stm3210e-eval/nsh2/defconfig b/nuttx/configs/stm3210e-eval/nsh2/defconfig index d4fa891fb..c30691cc9 100644 --- a/nuttx/configs/stm3210e-eval/nsh2/defconfig +++ b/nuttx/configs/stm3210e-eval/nsh2/defconfig @@ -538,20 +538,20 @@ CONFIG_LCD_PWM=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/stm3210e-eval/nx/defconfig b/nuttx/configs/stm3210e-eval/nx/defconfig index cab297583..0833e7a78 100644 --- a/nuttx/configs/stm3210e-eval/nx/defconfig +++ b/nuttx/configs/stm3210e-eval/nx/defconfig @@ -462,20 +462,20 @@ CONFIG_LCD_PWM=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/stm3210e-eval/nxconsole/defconfig b/nuttx/configs/stm3210e-eval/nxconsole/defconfig index 35ba0dcc1..637967efc 100644 --- a/nuttx/configs/stm3210e-eval/nxconsole/defconfig +++ b/nuttx/configs/stm3210e-eval/nxconsole/defconfig @@ -463,20 +463,20 @@ CONFIG_LCD_PWM=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/stm3210e-eval/nxlines/defconfig b/nuttx/configs/stm3210e-eval/nxlines/defconfig index b81f4127c..0a124407a 100644 --- a/nuttx/configs/stm3210e-eval/nxlines/defconfig +++ b/nuttx/configs/stm3210e-eval/nxlines/defconfig @@ -461,20 +461,20 @@ CONFIG_LCD_PWM=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/stm3210e-eval/nxtext/defconfig b/nuttx/configs/stm3210e-eval/nxtext/defconfig index 22dd209a9..14e20946e 100644 --- a/nuttx/configs/stm3210e-eval/nxtext/defconfig +++ b/nuttx/configs/stm3210e-eval/nxtext/defconfig @@ -461,20 +461,20 @@ CONFIG_LCD_PWM=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/stm3210e-eval/ostest/defconfig b/nuttx/configs/stm3210e-eval/ostest/defconfig index 7a2e5b528..8585235ec 100755 --- a/nuttx/configs/stm3210e-eval/ostest/defconfig +++ b/nuttx/configs/stm3210e-eval/ostest/defconfig @@ -398,20 +398,20 @@ CONFIG_WATCHDOG=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/stm3210e-eval/pm/defconfig b/nuttx/configs/stm3210e-eval/pm/defconfig index 6ca7cda87..f7ae420e4 100644 --- a/nuttx/configs/stm3210e-eval/pm/defconfig +++ b/nuttx/configs/stm3210e-eval/pm/defconfig @@ -569,34 +569,34 @@ CONFIG_LCD_PWM=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/buttons # -CONFIG_EXAMPLE_IRQBUTTONS_MIN=0 -CONFIG_EXAMPLE_IRQBUTTONS_MAX=7 -CONFIG_EXAMPLE_BUTTONS_NAME0="WAKEUP" -CONFIG_EXAMPLE_BUTTONS_NAME1="TAMPER" -CONFIG_EXAMPLE_BUTTONS_NAME2="KEY" -CONFIG_EXAMPLE_BUTTONS_NAME3="SELECT" -CONFIG_EXAMPLE_BUTTONS_NAME4="DOWN" -CONFIG_EXAMPLE_BUTTONS_NAME5="LEFT" -CONFIG_EXAMPLE_BUTTONS_NAME6="RIGHT" -CONFIG_EXAMPLE_BUTTONS_NAME7="UP" +CONFIG_EXAMPLES_IRQBUTTONS_MIN=0 +CONFIG_EXAMPLES_IRQBUTTONS_MAX=7 +CONFIG_EXAMPLES_BUTTONS_NAME0="WAKEUP" +CONFIG_EXAMPLES_BUTTONS_NAME1="TAMPER" +CONFIG_EXAMPLES_BUTTONS_NAME2="KEY" +CONFIG_EXAMPLES_BUTTONS_NAME3="SELECT" +CONFIG_EXAMPLES_BUTTONS_NAME4="DOWN" +CONFIG_EXAMPLES_BUTTONS_NAME5="LEFT" +CONFIG_EXAMPLES_BUTTONS_NAME6="RIGHT" +CONFIG_EXAMPLES_BUTTONS_NAME7="UP" # # Settings for examples/ostest diff --git a/nuttx/configs/stm3210e-eval/usbserial/defconfig b/nuttx/configs/stm3210e-eval/usbserial/defconfig index 99a5e2572..ac3ff1c9a 100755 --- a/nuttx/configs/stm3210e-eval/usbserial/defconfig +++ b/nuttx/configs/stm3210e-eval/usbserial/defconfig @@ -413,20 +413,20 @@ CONFIG_WATCHDOG=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/stm3210e-eval/usbstorage/defconfig b/nuttx/configs/stm3210e-eval/usbstorage/defconfig index 812226ee6..160d95237 100755 --- a/nuttx/configs/stm3210e-eval/usbstorage/defconfig +++ b/nuttx/configs/stm3210e-eval/usbstorage/defconfig @@ -395,20 +395,20 @@ CONFIG_WATCHDOG=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/stm3220g-eval/README.txt b/nuttx/configs/stm3220g-eval/README.txt index 89c6b9233..22038893e 100644 --- a/nuttx/configs/stm3220g-eval/README.txt +++ b/nuttx/configs/stm3220g-eval/README.txt @@ -724,11 +724,11 @@ Where is one of the following: using the STM32's Ethernet controller. It uses apps/examples/nettest to excercise the TCP/IP network. - CONFIG_EXAMPLE_NETTEST_SERVER=n : Target is configured as the client - CONFIG_EXAMPLE_NETTEST_PERFORMANCE=y : Only network performance is verified. - CONFIG_EXAMPLE_NETTEST_IPADDR=(10<<24|0<<16|0<<8|2) : Target side is IP: 10.0.0.2 - CONFIG_EXAMPLE_NETTEST_DRIPADDR=(10<<24|0<<16|0<<8|1) : Host side is IP: 10.0.0.1 - CONFIG_EXAMPLE_NETTEST_CLIENTIP=(10<<24|0<<16|0<<8|1) : Server address used by which ever is client. + CONFIG_EXAMPLES_NETTEST_SERVER=n : Target is configured as the client + CONFIG_EXAMPLES_NETTEST_PERFORMANCE=y : Only network performance is verified. + CONFIG_EXAMPLES_NETTEST_IPADDR=(10<<24|0<<16|0<<8|2) : Target side is IP: 10.0.0.2 + CONFIG_EXAMPLES_NETTEST_DRIPADDR=(10<<24|0<<16|0<<8|1) : Host side is IP: 10.0.0.1 + CONFIG_EXAMPLES_NETTEST_CLIENTIP=(10<<24|0<<16|0<<8|1) : Server address used by which ever is client. nsh: --- diff --git a/nuttx/configs/stm3220g-eval/dhcpd/defconfig b/nuttx/configs/stm3220g-eval/dhcpd/defconfig index d011a3bfb..762607bd0 100644 --- a/nuttx/configs/stm3220g-eval/dhcpd/defconfig +++ b/nuttx/configs/stm3220g-eval/dhcpd/defconfig @@ -523,28 +523,28 @@ CONFIG_NX_MXCLIENTMSGS=16 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/dhcpd # -CONFIG_EXAMPLE_DHCPD_NOMAC=y -CONFIG_EXAMPLE_DHCPD_IPADDR=0x0a000001 -CONFIG_EXAMPLE_DHCPD_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_DHCPD_NETMASK=0xffffff00 +CONFIG_EXAMPLES_DHCPD_NOMAC=y +CONFIG_EXAMPLES_DHCPD_IPADDR=0x0a000001 +CONFIG_EXAMPLES_DHCPD_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_DHCPD_NETMASK=0xffffff00 # # Settings for examples/ostest diff --git a/nuttx/configs/stm3220g-eval/nettest/defconfig b/nuttx/configs/stm3220g-eval/nettest/defconfig index 48a7982c2..9262e8c24 100644 --- a/nuttx/configs/stm3220g-eval/nettest/defconfig +++ b/nuttx/configs/stm3220g-eval/nettest/defconfig @@ -523,21 +523,21 @@ CONFIG_NX_MXCLIENTMSGS=16 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=y -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=y +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/stm3220g-eval/nsh/defconfig b/nuttx/configs/stm3220g-eval/nsh/defconfig index 1f8cac1f1..ca1d914de 100644 --- a/nuttx/configs/stm3220g-eval/nsh/defconfig +++ b/nuttx/configs/stm3220g-eval/nsh/defconfig @@ -639,20 +639,20 @@ CONFIG_STM32_ILI9325_DISABLE=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/stm3220g-eval/nsh2/defconfig b/nuttx/configs/stm3220g-eval/nsh2/defconfig index 8462ef376..324c920d7 100644 --- a/nuttx/configs/stm3220g-eval/nsh2/defconfig +++ b/nuttx/configs/stm3220g-eval/nsh2/defconfig @@ -626,20 +626,20 @@ CONFIG_STM32_ILI9325_DISABLE=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/stm3220g-eval/nxwm/defconfig b/nuttx/configs/stm3220g-eval/nxwm/defconfig index 83c2f4841..41f365257 100644 --- a/nuttx/configs/stm3220g-eval/nxwm/defconfig +++ b/nuttx/configs/stm3220g-eval/nxwm/defconfig @@ -670,20 +670,20 @@ CONFIG_STM32_ILI9325_DISABLE=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/stm3220g-eval/ostest/defconfig b/nuttx/configs/stm3220g-eval/ostest/defconfig index 5fc04f03c..b8663a72a 100644 --- a/nuttx/configs/stm3220g-eval/ostest/defconfig +++ b/nuttx/configs/stm3220g-eval/ostest/defconfig @@ -529,20 +529,20 @@ CONFIG_STM32_ILI9325_DISABLE=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest @@ -661,13 +661,13 @@ CONFIG_EXAMPLES_TOUCHSCREEN_NSAMPLES=25 # # Settings for examples/buttons # -CONFIG_EXAMPLE_BUTTONS_MIN=0 -CONFIG_EXAMPLE_BUTTONS_MAX=2 -CONFIG_EXAMPLE_IRQBUTTONS_MIN=0 -CONFIG_EXAMPLE_IRQBUTTONS_MAX=2 -CONFIG_EXAMPLE_BUTTONS_NAME0="Key/Select" -CONFIG_EXAMPLE_BUTTONS_NAME1="Left/Right" -CONFIG_EXAMPLE_BUTTONS_NAME2="Up/Down" +CONFIG_EXAMPLES_BUTTONS_MIN=0 +CONFIG_EXAMPLES_BUTTONS_MAX=2 +CONFIG_EXAMPLES_IRQBUTTONS_MIN=0 +CONFIG_EXAMPLES_IRQBUTTONS_MAX=2 +CONFIG_EXAMPLES_BUTTONS_NAME0="Key/Select" +CONFIG_EXAMPLES_BUTTONS_NAME1="Left/Right" +CONFIG_EXAMPLES_BUTTONS_NAME2="Up/Down" # # I2C tool settings diff --git a/nuttx/configs/stm3220g-eval/telnetd/defconfig b/nuttx/configs/stm3220g-eval/telnetd/defconfig index e369a522e..28670bb47 100644 --- a/nuttx/configs/stm3220g-eval/telnetd/defconfig +++ b/nuttx/configs/stm3220g-eval/telnetd/defconfig @@ -523,21 +523,21 @@ CONFIG_NX_MXCLIENTMSGS=16 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=y -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=y +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/telnetd @@ -546,10 +546,10 @@ CONFIG_EXAMPLES_TELNETD_DAEMONPRIO=128 CONFIG_EXAMPLES_TELNETD_DAEMONSTACKSIZE=2048 CONFIG_EXAMPLES_TELNETD_CLIENTPRIO=128 CONFIG_EXAMPLES_TELNETD_CLIENTSTACKSIZE=2048 -CONFIG_EXAMPLE_TELNETD_NOMAC=y -CONFIG_EXAMPLE_TELNETD_IPADDR=0x0a000002 -CONFIG_EXAMPLE_TELNETD_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_TELNETD_NETMASK=0xffffff00 +CONFIG_EXAMPLES_TELNETD_NOMAC=y +CONFIG_EXAMPLES_TELNETD_IPADDR=0x0a000002 +CONFIG_EXAMPLES_TELNETD_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_TELNETD_NETMASK=0xffffff00 # # Settings for examples/ostest diff --git a/nuttx/configs/stm3240g-eval/README.txt b/nuttx/configs/stm3240g-eval/README.txt index b536097a8..a1a596bae 100644 --- a/nuttx/configs/stm3240g-eval/README.txt +++ b/nuttx/configs/stm3240g-eval/README.txt @@ -893,10 +893,10 @@ Where is one of the following: Configuration settings that you may need to change for your environment: - CONFIG_STM32_CODESOURCERYL=y - CodeSourcery for Linux - CONFIG_EXAMPLE_DISCOVER_DHCPC=y - DHCP Client - CONFIG_EXAMPLE_DISCOVER_IPADDR - (not defined) - CONFIG_EXAMPLE_DISCOVER_DRIPADDR - Router IP address + CONFIG_STM32_CODESOURCERYL=y - CodeSourcery for Linux + CONFIG_EXAMPLES_DISCOVER_DHCPC=y - DHCP Client + CONFIG_EXAMPLES_DISCOVER_IPADDR - (not defined) + CONFIG_EXAMPLES_DISCOVER_DRIPADDR - Router IP address NOTE: This configuration uses to the mconf configuration tool to control the configuration. See the section entitled "NuttX Configuration Tool" @@ -909,11 +909,11 @@ Where is one of the following: using the STM32's Ethernet controller. It uses apps/examples/nettest to excercise the TCP/IP network. - CONFIG_EXAMPLE_NETTEST_SERVER=n : Target is configured as the client - CONFIG_EXAMPLE_NETTEST_PERFORMANCE=y : Only network performance is verified. - CONFIG_EXAMPLE_NETTEST_IPADDR=(10<<24|0<<16|0<<8|2) : Target side is IP: 10.0.0.2 - CONFIG_EXAMPLE_NETTEST_DRIPADDR=(10<<24|0<<16|0<<8|1) : Host side is IP: 10.0.0.1 - CONFIG_EXAMPLE_NETTEST_CLIENTIP=(10<<24|0<<16|0<<8|1) : Server address used by which ever is client. + CONFIG_EXAMPLES_NETTEST_SERVER=n : Target is configured as the client + CONFIG_EXAMPLES_NETTEST_PERFORMANCE=y : Only network performance is verified. + CONFIG_EXAMPLES_NETTEST_IPADDR=(10<<24|0<<16|0<<8|2) : Target side is IP: 10.0.0.2 + CONFIG_EXAMPLES_NETTEST_DRIPADDR=(10<<24|0<<16|0<<8|1) : Host side is IP: 10.0.0.1 + CONFIG_EXAMPLES_NETTEST_CLIENTIP=(10<<24|0<<16|0<<8|1) : Server address used by which ever is client. nsh: --- diff --git a/nuttx/configs/stm3240g-eval/dhcpd/defconfig b/nuttx/configs/stm3240g-eval/dhcpd/defconfig index 842e0c66b..e33b62f87 100644 --- a/nuttx/configs/stm3240g-eval/dhcpd/defconfig +++ b/nuttx/configs/stm3240g-eval/dhcpd/defconfig @@ -536,28 +536,28 @@ CONFIG_NX_MXCLIENTMSGS=16 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/dhcpd # -CONFIG_EXAMPLE_DHCPD_NOMAC=y -CONFIG_EXAMPLE_DHCPD_IPADDR=0x0a000001 -CONFIG_EXAMPLE_DHCPD_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_DHCPD_NETMASK=0xffffff00 +CONFIG_EXAMPLES_DHCPD_NOMAC=y +CONFIG_EXAMPLES_DHCPD_IPADDR=0x0a000001 +CONFIG_EXAMPLES_DHCPD_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_DHCPD_NETMASK=0xffffff00 # # Settings for examples/ostest diff --git a/nuttx/configs/stm3240g-eval/discover/defconfig b/nuttx/configs/stm3240g-eval/discover/defconfig index 12075b891..7c1163b9b 100644 --- a/nuttx/configs/stm3240g-eval/discover/defconfig +++ b/nuttx/configs/stm3240g-eval/discover/defconfig @@ -714,11 +714,11 @@ CONFIG_HAVE_CXXINITIALIZE=y # # UDP Discovery Daemon Example # -CONFIG_EXAMPLE_DISCOVER=y -CONFIG_EXAMPLE_DISCOVER_DHCPC=y -CONFIG_EXAMPLE_DISCOVER_NOMAC=y -CONFIG_EXAMPLE_DISCOVER_DRIPADDR=0xc0a80201 -CONFIG_EXAMPLE_DISCOVER_NETMASK=0xffffff00 +CONFIG_EXAMPLES_DISCOVER=y +CONFIG_EXAMPLES_DISCOVER_DHCPC=y +CONFIG_EXAMPLES_DISCOVER_NOMAC=y +CONFIG_EXAMPLES_DISCOVER_DRIPADDR=0xc0a80201 +CONFIG_EXAMPLES_DISCOVER_NETMASK=0xffffff00 # # uIP Web Server Example diff --git a/nuttx/configs/stm3240g-eval/nettest/defconfig b/nuttx/configs/stm3240g-eval/nettest/defconfig index 55ac14157..813912b84 100644 --- a/nuttx/configs/stm3240g-eval/nettest/defconfig +++ b/nuttx/configs/stm3240g-eval/nettest/defconfig @@ -536,21 +536,21 @@ CONFIG_NX_MXCLIENTMSGS=16 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=y -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=y +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/stm3240g-eval/nsh/defconfig b/nuttx/configs/stm3240g-eval/nsh/defconfig index 653538b45..8c7c29078 100644 --- a/nuttx/configs/stm3240g-eval/nsh/defconfig +++ b/nuttx/configs/stm3240g-eval/nsh/defconfig @@ -639,20 +639,20 @@ CONFIG_STM32_ILI9325_DISABLE=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/stm3240g-eval/nsh2/defconfig b/nuttx/configs/stm3240g-eval/nsh2/defconfig index 9d2591068..53b0896d8 100644 --- a/nuttx/configs/stm3240g-eval/nsh2/defconfig +++ b/nuttx/configs/stm3240g-eval/nsh2/defconfig @@ -586,20 +586,20 @@ CONFIG_NX_MXCLIENTMSGS=16 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/stm3240g-eval/nxconsole/defconfig b/nuttx/configs/stm3240g-eval/nxconsole/defconfig index e7d27bd2e..f87acc69e 100644 --- a/nuttx/configs/stm3240g-eval/nxconsole/defconfig +++ b/nuttx/configs/stm3240g-eval/nxconsole/defconfig @@ -609,20 +609,20 @@ CONFIG_STM32_ILI9325_DISABLE=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/stm3240g-eval/nxwm/defconfig b/nuttx/configs/stm3240g-eval/nxwm/defconfig index c90051b9b..d1fa395dd 100644 --- a/nuttx/configs/stm3240g-eval/nxwm/defconfig +++ b/nuttx/configs/stm3240g-eval/nxwm/defconfig @@ -670,20 +670,20 @@ CONFIG_STM32_ILI9325_DISABLE=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/stm3240g-eval/ostest/defconfig b/nuttx/configs/stm3240g-eval/ostest/defconfig index bfc576f5f..cc7a9ac58 100644 --- a/nuttx/configs/stm3240g-eval/ostest/defconfig +++ b/nuttx/configs/stm3240g-eval/ostest/defconfig @@ -541,20 +541,20 @@ CONFIG_STM32_ILI9325_DISABLE=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest @@ -673,13 +673,13 @@ CONFIG_EXAMPLES_TOUCHSCREEN_NSAMPLES=25 # # Settings for examples/buttons # -CONFIG_EXAMPLE_BUTTONS_MIN=0 -CONFIG_EXAMPLE_BUTTONS_MAX=2 -CONFIG_EXAMPLE_IRQBUTTONS_MIN=0 -CONFIG_EXAMPLE_IRQBUTTONS_MAX=2 -CONFIG_EXAMPLE_BUTTONS_NAME0="Key/Select" -CONFIG_EXAMPLE_BUTTONS_NAME1="Left/Right" -CONFIG_EXAMPLE_BUTTONS_NAME2="Up/Down" +CONFIG_EXAMPLES_BUTTONS_MIN=0 +CONFIG_EXAMPLES_BUTTONS_MAX=2 +CONFIG_EXAMPLES_IRQBUTTONS_MIN=0 +CONFIG_EXAMPLES_IRQBUTTONS_MAX=2 +CONFIG_EXAMPLES_BUTTONS_NAME0="Key/Select" +CONFIG_EXAMPLES_BUTTONS_NAME1="Left/Right" +CONFIG_EXAMPLES_BUTTONS_NAME2="Up/Down" # # I2C tool settings diff --git a/nuttx/configs/stm3240g-eval/telnetd/defconfig b/nuttx/configs/stm3240g-eval/telnetd/defconfig index f138e5e6f..4ab86aeb9 100644 --- a/nuttx/configs/stm3240g-eval/telnetd/defconfig +++ b/nuttx/configs/stm3240g-eval/telnetd/defconfig @@ -536,21 +536,21 @@ CONFIG_NX_MXCLIENTMSGS=16 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=y -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=y +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/telnetd @@ -559,10 +559,10 @@ CONFIG_EXAMPLES_TELNETD_DAEMONPRIO=128 CONFIG_EXAMPLES_TELNETD_DAEMONSTACKSIZE=2048 CONFIG_EXAMPLES_TELNETD_CLIENTPRIO=128 CONFIG_EXAMPLES_TELNETD_CLIENTSTACKSIZE=2048 -CONFIG_EXAMPLE_TELNETD_NOMAC=y -CONFIG_EXAMPLE_TELNETD_IPADDR=0x0a000002 -CONFIG_EXAMPLE_TELNETD_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_TELNETD_NETMASK=0xffffff00 +CONFIG_EXAMPLES_TELNETD_NOMAC=y +CONFIG_EXAMPLES_TELNETD_IPADDR=0x0a000002 +CONFIG_EXAMPLES_TELNETD_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_TELNETD_NETMASK=0xffffff00 # # Settings for examples/ostest diff --git a/nuttx/configs/stm3240g-eval/webserver/defconfig b/nuttx/configs/stm3240g-eval/webserver/defconfig index 25f1800b6..8921d503c 100644 --- a/nuttx/configs/stm3240g-eval/webserver/defconfig +++ b/nuttx/configs/stm3240g-eval/webserver/defconfig @@ -639,21 +639,21 @@ CONFIG_STM32_ILI9325_DISABLE=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0xc0a80232 -CONFIG_EXAMPLE_UIP_DRIPADDR=0xc0a80201 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_NOMAC=y -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0xc0a80232 +CONFIG_EXAMPLES_UIP_DRIPADDR=0xc0a80201 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_NOMAC=y +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/stm3240g-eval/xmlrpc/defconfig b/nuttx/configs/stm3240g-eval/xmlrpc/defconfig index c2ba860fa..20639dac4 100644 --- a/nuttx/configs/stm3240g-eval/xmlrpc/defconfig +++ b/nuttx/configs/stm3240g-eval/xmlrpc/defconfig @@ -707,7 +707,7 @@ CONFIG_HAVE_CXXINITIALIZE=y # # UDP Discovery Daemon Example # -# CONFIG_EXAMPLE_DISCOVER is not set +# CONFIG_EXAMPLES_DISCOVER is not set # # uIP Web Server Example diff --git a/nuttx/configs/stm32f4discovery/nsh/defconfig b/nuttx/configs/stm32f4discovery/nsh/defconfig index 38a0a1e03..c216c5997 100644 --- a/nuttx/configs/stm32f4discovery/nsh/defconfig +++ b/nuttx/configs/stm32f4discovery/nsh/defconfig @@ -579,20 +579,20 @@ CONFIG_NX_MXCLIENTMSGS=16 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/stm32f4discovery/nxlines/defconfig b/nuttx/configs/stm32f4discovery/nxlines/defconfig index bbdbf0fea..e1e4f2131 100644 --- a/nuttx/configs/stm32f4discovery/nxlines/defconfig +++ b/nuttx/configs/stm32f4discovery/nxlines/defconfig @@ -590,21 +590,21 @@ CONFIG_LCD_RPORTRAIT=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/stm32f4discovery/ostest/defconfig b/nuttx/configs/stm32f4discovery/ostest/defconfig index a10efe9ec..dba07f76b 100644 --- a/nuttx/configs/stm32f4discovery/ostest/defconfig +++ b/nuttx/configs/stm32f4discovery/ostest/defconfig @@ -546,20 +546,20 @@ CONFIG_STM32_R61580_DISABLE=n # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest @@ -678,13 +678,13 @@ CONFIG_EXAMPLES_TOUCHSCREEN_NSAMPLES=25 # # Settings for examples/buttons # -CONFIG_EXAMPLE_BUTTONS_MIN=0 -CONFIG_EXAMPLE_BUTTONS_MAX=2 -CONFIG_EXAMPLE_IRQBUTTONS_MIN=0 -CONFIG_EXAMPLE_IRQBUTTONS_MAX=2 -CONFIG_EXAMPLE_BUTTONS_NAME0="Key/Select" -CONFIG_EXAMPLE_BUTTONS_NAME1="Left/Right" -CONFIG_EXAMPLE_BUTTONS_NAME2="Up/Down" +CONFIG_EXAMPLES_BUTTONS_MIN=0 +CONFIG_EXAMPLES_BUTTONS_MAX=2 +CONFIG_EXAMPLES_IRQBUTTONS_MIN=0 +CONFIG_EXAMPLES_IRQBUTTONS_MAX=2 +CONFIG_EXAMPLES_BUTTONS_NAME0="Key/Select" +CONFIG_EXAMPLES_BUTTONS_NAME1="Left/Right" +CONFIG_EXAMPLES_BUTTONS_NAME2="Up/Down" # # Settings for examples/usbserial diff --git a/nuttx/configs/stm32f4discovery/pm/defconfig b/nuttx/configs/stm32f4discovery/pm/defconfig index 8960253f9..07a99c764 100644 --- a/nuttx/configs/stm32f4discovery/pm/defconfig +++ b/nuttx/configs/stm32f4discovery/pm/defconfig @@ -598,20 +598,20 @@ CONFIG_NX_MXCLIENTMSGS=16 # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/sure-pic32mx/nsh/defconfig b/nuttx/configs/sure-pic32mx/nsh/defconfig index ffd95e4ac..8025f968c 100644 --- a/nuttx/configs/sure-pic32mx/nsh/defconfig +++ b/nuttx/configs/sure-pic32mx/nsh/defconfig @@ -409,21 +409,21 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/sure-pic32mx/ostest/defconfig b/nuttx/configs/sure-pic32mx/ostest/defconfig index 731529df8..f3c3fee36 100644 --- a/nuttx/configs/sure-pic32mx/ostest/defconfig +++ b/nuttx/configs/sure-pic32mx/ostest/defconfig @@ -364,21 +364,21 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/sure-pic32mx/usbnsh/defconfig b/nuttx/configs/sure-pic32mx/usbnsh/defconfig index 0abcd72b8..cdebb2953 100644 --- a/nuttx/configs/sure-pic32mx/usbnsh/defconfig +++ b/nuttx/configs/sure-pic32mx/usbnsh/defconfig @@ -406,21 +406,21 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/teensy/hello/defconfig b/nuttx/configs/teensy/hello/defconfig index dee8b264e..83176f57e 100644 --- a/nuttx/configs/teensy/hello/defconfig +++ b/nuttx/configs/teensy/hello/defconfig @@ -313,21 +313,21 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/teensy/nsh/defconfig b/nuttx/configs/teensy/nsh/defconfig index 32b7e5a41..0908f0243 100755 --- a/nuttx/configs/teensy/nsh/defconfig +++ b/nuttx/configs/teensy/nsh/defconfig @@ -324,21 +324,21 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/teensy/usbstorage/defconfig b/nuttx/configs/teensy/usbstorage/defconfig index 68d54b870..94cc301db 100755 --- a/nuttx/configs/teensy/usbstorage/defconfig +++ b/nuttx/configs/teensy/usbstorage/defconfig @@ -332,21 +332,21 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/twr-k60n512/nsh/defconfig b/nuttx/configs/twr-k60n512/nsh/defconfig index 47aecfea6..d8ccd6a6d 100644 --- a/nuttx/configs/twr-k60n512/nsh/defconfig +++ b/nuttx/configs/twr-k60n512/nsh/defconfig @@ -378,20 +378,20 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/twr-k60n512/ostest/defconfig b/nuttx/configs/twr-k60n512/ostest/defconfig index 984ff5cff..8909add13 100644 --- a/nuttx/configs/twr-k60n512/ostest/defconfig +++ b/nuttx/configs/twr-k60n512/ostest/defconfig @@ -376,20 +376,20 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/ubw32/nsh/defconfig b/nuttx/configs/ubw32/nsh/defconfig index cfc0dad30..afa4e10c8 100644 --- a/nuttx/configs/ubw32/nsh/defconfig +++ b/nuttx/configs/ubw32/nsh/defconfig @@ -396,21 +396,21 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/ubw32/ostest/defconfig b/nuttx/configs/ubw32/ostest/defconfig index 0fc2984bc..0849fe800 100644 --- a/nuttx/configs/ubw32/ostest/defconfig +++ b/nuttx/configs/ubw32/ostest/defconfig @@ -395,21 +395,21 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest # -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=y -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=y +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest diff --git a/nuttx/configs/vsn/nsh/defconfig b/nuttx/configs/vsn/nsh/defconfig index c55fae0f3..8c59b4298 100755 --- a/nuttx/configs/vsn/nsh/defconfig +++ b/nuttx/configs/vsn/nsh/defconfig @@ -426,20 +426,20 @@ CONFIG_USBMSC_REMOVABLE=y # # Settings for examples/uip # -CONFIG_EXAMPLE_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLE_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLE_UIP_DHCPC=n +CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 +CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_EXAMPLES_UIP_DHCPC=n # # Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLE_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLE_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLE_NETTEST_CLIENTIP=0x0a000001 +CONFIG_EXAMPLES_NETTEST_SERVER=n +CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLES_NETTEST_NOMAC=n +CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 +CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 +CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 +CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 # # Settings for examples/ostest -- cgit v1.2.3 From eb041b927ae19ab2b8ccbd89ae264b1c42c4a017 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 4 Oct 2012 18:42:28 +0000 Subject: Fix some W25 driver errors git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5212 42af7a65-404d-4744-a932-0658087f49c3 --- apps/ChangeLog.txt | 2 ++ apps/examples/README.txt | 4 +-- apps/examples/buttons/Kconfig | 52 ++++++++++++++++++++++++++++++++- nuttx/ChangeLog | 2 ++ nuttx/configs/fire-stm32v2/src/up_w25.c | 12 ++++---- nuttx/configs/shenzhou/src/up_ili93xx.c | 2 +- nuttx/configs/shenzhou/src/up_w25.c | 12 ++++---- nuttx/drivers/mtd/w25.c | 21 ++++--------- nuttx/fs/nxffs/Kconfig | 16 +++++----- 9 files changed, 84 insertions(+), 39 deletions(-) (limited to 'nuttx') diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index 397ccdac4..bf2a85a9b 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -362,3 +362,5 @@ of CONFIG_EXAMPLE_* to CONFIG_EXAMPLES_*. * Kconfig: Fleshed out apps/examples/adc/Kconfig and apps/examples/wget/Kconfig. There are still a LOT of empty, stub Kconfig files. + * Kconfig: Fleshed out apps/examples/buttons/Kconfig. There are still a LOT + of empty, stub Kconfig files. diff --git a/apps/examples/README.txt b/apps/examples/README.txt index 7ef51025f..763427e32 100644 --- a/apps/examples/README.txt +++ b/apps/examples/README.txt @@ -60,11 +60,11 @@ examples/buttons This is a simple configuration that may be used to test the board- specific button interfaces. Configuration options: - CONFIG_ARCH_BUTTONS - Must be defined for button support + CONFIG_ARCH_BUTTONS - Must be defined for button support CONFIG_EXAMPLES_BUTTONS_MIN - Lowest button number (MIN=0) CONFIG_EXAMPLES_BUTTONS_MAX - Highest button number (MAX=7) - CONFIG_ARCH_IRQBUTTONS - Must be defined for interrupting button support + CONFIG_ARCH_IRQBUTTONS - Must be defined for interrupting button support CONFIG_EXAMPLES_IRQBUTTONS_MIN - Lowest interrupting button number (MIN=0) CONFIG_EXAMPLES_IRQBUTTONS_MAX - Highest interrupting button number (MAX=7) diff --git a/apps/examples/buttons/Kconfig b/apps/examples/buttons/Kconfig index 9c34b37bc..d145867fc 100644 --- a/apps/examples/buttons/Kconfig +++ b/apps/examples/buttons/Kconfig @@ -7,7 +7,57 @@ config EXAMPLES_BUTTONS bool "Buttons example" default n ---help--- - Enable the buttons example + Enable the buttons example. May require ARCH_BUTTONS on some boards. if EXAMPLES_BUTTONS +config EXAMPLES_BUTTONS_MIN +int "Lowest Button Number" +default 0 + +config EXAMPLES_BUTTONS_MAX +int "Highest Button Number" +default 7 + +if ARCH_IRQBUTTONS +config EXAMPLES_IRQBUTTONS_MIN +int "Lowest Interrupting Button Number" +default 0 + +config EXAMPLES_IRQBUTTONS_MAX +int "Highest Interrupting Button Number" +default 7 + +config EXAMPLES_BUTTONS_NAME0 +string "Button 0 Name" +default "Button 0" + +config EXAMPLES_BUTTONS_NAME1 +string "Button 1 Name" +default "Button 1" + +config EXAMPLES_BUTTONS_NAME2 +string "Button 2 Name" +default "Button 2" + +config EXAMPLES_BUTTONS_NAME3 +string "Button 3 Name" +default "Button 3" + +config EXAMPLES_BUTTONS_NAME4 +string "Button 4 Name" +default "Button 4" + +config EXAMPLES_BUTTONS_NAME5 +string "Button 5 Name" +default "Button 5" + +config EXAMPLES_BUTTONS_NAME6 +string "Button 6 Name" +default "Button 6" + +config EXAMPLES_BUTTONS_NAME7 +string "Button 7 Name" +default "Button 7" + +endif endif diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index eb85a8e7c..257119a35 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3463,3 +3463,5 @@ by the STM32 watchdog driver. * CONFIG_EXAMPLES_*: To make things consistent, changed all occurrences of CONFIG_EXAMPLE_* to CONFIG_EXAMPLES_*. + * drivers/mtd/w25.c and configs/*/src/up_w25.c: Several fixes for the + W25 SPI FLASH. diff --git a/nuttx/configs/fire-stm32v2/src/up_w25.c b/nuttx/configs/fire-stm32v2/src/up_w25.c index a3460a158..e78b50ed2 100644 --- a/nuttx/configs/fire-stm32v2/src/up_w25.c +++ b/nuttx/configs/fire-stm32v2/src/up_w25.c @@ -96,23 +96,23 @@ int stm32_w25initialize(int minor) #ifdef HAVE_W25 FAR struct spi_dev_s *spi; FAR struct mtd_dev_s *mtd; -#ifndef CONFIG_FS_NXFFS - uint8_t devname[12]; +#ifdef CONFIG_FS_NXFFS + char devname[12]; #endif int ret; /* Get the SPI port */ - spi = up_spiinitialize(2); + spi = up_spiinitialize(1); if (!spi) { fdbg("ERROR: Failed to initialize SPI port 2\n"); return -ENODEV; } - /* Now bind the SPI interface to the SST 25 SPI FLASH driver */ + /* Now bind the SPI interface to the W25 SPI FLASH driver */ - mtd = sst25_initialize(spi); + mtd = w25_initialize(spi); if (!mtd) { fdbg("ERROR: Failed to bind SPI port 2 to the SST 25 FLASH driver\n"); @@ -140,7 +140,7 @@ int stm32_w25initialize(int minor) /* Mount the file system at /mnt/w25 */ - snprintf(devname, 12, "/mnt/w25%c", a + minor); + snprintf(devname, 12, "/mnt/w25%c", 'a' + minor); ret = mount(NULL, devname, "nxffs", 0, NULL); if (ret < 0) { diff --git a/nuttx/configs/shenzhou/src/up_ili93xx.c b/nuttx/configs/shenzhou/src/up_ili93xx.c index d3e2291da..a89e20d02 100644 --- a/nuttx/configs/shenzhou/src/up_ili93xx.c +++ b/nuttx/configs/shenzhou/src/up_ili93xx.c @@ -805,7 +805,7 @@ static uint16_t stm32_readnoshift(FAR struct stm32_dev_s *priv, FAR uint16_t *ac static void stm32_setcursor(FAR struct stm32_dev_s *priv, uint16_t col, uint16_t row) { - if (priv->type = LCD_TYPE_ILI9919) + if (priv->type == LCD_TYPE_ILI9919) { stm32_writereg(priv, LCD_REG_78, col); /* GRAM horizontal address */ stm32_writereg(priv, LCD_REG_79, row); /* GRAM vertical address */ diff --git a/nuttx/configs/shenzhou/src/up_w25.c b/nuttx/configs/shenzhou/src/up_w25.c index aa547f6fe..01936997f 100644 --- a/nuttx/configs/shenzhou/src/up_w25.c +++ b/nuttx/configs/shenzhou/src/up_w25.c @@ -96,23 +96,23 @@ int stm32_w25initialize(int minor) #ifdef HAVE_W25 FAR struct spi_dev_s *spi; FAR struct mtd_dev_s *mtd; -#ifndef CONFIG_FS_NXFFS - uint8_t devname[12]; +#ifdef CONFIG_FS_NXFFS + char devname[12]; #endif int ret; /* Get the SPI port */ - spi = up_spiinitialize(2); + spi = up_spiinitialize(1); if (!spi) { fdbg("ERROR: Failed to initialize SPI port 2\n"); return -ENODEV; } - /* Now bind the SPI interface to the SST 25 SPI FLASH driver */ + /* Now bind the SPI interface to the W25 SPI FLASH driver */ - mtd = sst25_initialize(spi); + mtd = w25_initialize(spi); if (!mtd) { fdbg("ERROR: Failed to bind SPI port 2 to the SST 25 FLASH driver\n"); @@ -140,7 +140,7 @@ int stm32_w25initialize(int minor) /* Mount the file system at /mnt/w25 */ - snprintf(devname, 12, "/mnt/w25%c", a + minor); + snprintf(devname, 12, "/mnt/w25%c", 'a' + minor); ret = mount(NULL, devname, "nxffs", 0, NULL); if (ret < 0) { diff --git a/nuttx/drivers/mtd/w25.c b/nuttx/drivers/mtd/w25.c index 0d7028fec..bd6680fdf 100644 --- a/nuttx/drivers/mtd/w25.c +++ b/nuttx/drivers/mtd/w25.c @@ -693,7 +693,7 @@ static void w25_pagewrite(struct w25_dev_s *priv, FAR const uint8_t *buffer, uint8_t status; fvdbg("address: %08lx nwords: %d\n", (long)address, (int)nbytes); - DEBUGASSERT(priv && buffer && ((uintptr_t)buffer & 0xff) == 0 && + DEBUGASSERT(priv && buffer && (address & 0xff) == 0 && (nbytes & 0xff) == 0); for (; nbytes > 0; nbytes -= W25_PAGE_SIZE) @@ -955,36 +955,27 @@ static int w25_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks static ssize_t w25_bread(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks, FAR uint8_t *buffer) { -#ifdef CONFIG_W25_SECTOR512 ssize_t nbytes; fvdbg("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks); /* On this device, we can handle the block read just like the byte-oriented read */ +#ifdef CONFIG_W25_SECTOR512 nbytes = w25_read(dev, startblock << W25_SECTOR512_SHIFT, nblocks << W25_SECTOR512_SHIFT, buffer); if (nbytes > 0) { - return nbytes >> W25_SECTOR512_SHIFT; + nbytes >>= W25_SECTOR512_SHIFT; } - - return (int)nbytes; #else - FAR struct w25_dev_s *priv = (FAR struct w25_dev_s *)dev; - ssize_t nbytes; - - fvdbg("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks); - - /* On this device, we can handle the block read just like the byte-oriented read */ - nbytes = w25_read(dev, startblock << W25_SECTOR_SHIFT, nblocks << W25_SECTOR_SHIFT, buffer); if (nbytes > 0) { - return nbytes >> W25_SECTOR_SHIFT; + nbytes >>= W25_SECTOR_SHIFT; } - - return (int)nbytes; #endif + + return nbytes; } /************************************************************************************ diff --git a/nuttx/fs/nxffs/Kconfig b/nuttx/fs/nxffs/Kconfig index b233e85ea..9f4ef8231 100644 --- a/nuttx/fs/nxffs/Kconfig +++ b/nuttx/fs/nxffs/Kconfig @@ -12,31 +12,31 @@ config FS_NXFFS if FS_NXFFS config NXFFS_ERASEDSTATE - bool "FLASH erased state" - default n + hex "FLASH erased state" + default 0xff ---help--- The erased state of FLASH. This must have one of the values of 0xff or 0x00. Default: 0xff. config NXFFS_PACKTHRESHOLD - bool "Re-packing threshold" - default n + int "Re-packing threshold" + default 32 ---help--- When packing flash file data, don't both with file chunks smaller than this number of data bytes. Default: 32. config NXFFS_MAXNAMLEN - bool "Maximum file name length" - default n + int "Maximum file name length" + default 255 ---help--- The maximum size of an NXFFS file name. Default: 255. config NXFFS_TAILTHRESHOLD - bool "Tail threshold" - default n + int "Tail threshold" + default 8192 ---help--- clean-up can either mean packing files together toward the end of the file or, if file are -- cgit v1.2.3 From 1e368791267c48b0e6c672ad3ed2ba9521740a70 Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 5 Oct 2012 23:01:51 +0000 Subject: Add buildroot support for binutils-2.22 and gcc-4.6.3; all buildroot tools are not called abc-nuttx-elf instead of abc-elf git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5213 42af7a65-404d-4744-a932-0658087f49c3 --- misc/buildroot/ChangeLog | 5 +- misc/buildroot/Config.in | 3 +- misc/buildroot/configs/arm-defconfig | 2 +- misc/buildroot/configs/arm7tdmi-defconfig-4.2.4 | 2 +- misc/buildroot/configs/arm7tdmi-defconfig-4.3.3 | 2 +- misc/buildroot/configs/arm920t-defconfig-4.2.4 | 2 +- misc/buildroot/configs/arm920t-defconfig-4.3.3 | 2 +- misc/buildroot/configs/arm926t-defconfig-4.2.4 | 2 +- misc/buildroot/configs/arm926t-defconfig-4.3.3 | 2 +- misc/buildroot/configs/arm926t-defconfig-nxflat | 2 +- misc/buildroot/configs/avr-defconfig-4.3.3 | 2 +- misc/buildroot/configs/avr-defconfig-4.5.2 | 2 +- misc/buildroot/configs/bfin-defconfig-4.2.4 | 2 +- misc/buildroot/configs/cortexm3-defconfig-4.3.3 | 2 +- misc/buildroot/configs/cortexm3-defconfig-nxflat | 2 +- .../configs/cortexm3-eabi-defconfig-4.6.3 | 123 ++++ misc/buildroot/configs/h8300_defconfig | 2 +- misc/buildroot/configs/i486-defconfig-4.3.3 | 2 +- misc/buildroot/configs/m32c-defconfig-4.2.4 | 2 +- misc/buildroot/configs/m32c-defconfig-4.3.3 | 2 +- misc/buildroot/configs/m68hc11-config | 2 +- misc/buildroot/configs/m68hc12-config-3.4.6 | 2 +- misc/buildroot/configs/m68hc12-config-4.3.3 | 2 +- misc/buildroot/configs/m68k-defconfig | 2 +- misc/buildroot/configs/m9s12x-config-3.3.6 | 2 +- misc/buildroot/configs/sh-defconfig | 2 +- .../toolchain/binutils/2.22/120-sh-conf.patch | 29 + .../binutils/2.22/300-001_ld_makefile_patch.patch | 24 + .../2.22/300-012_check_ldrunpath_length.patch | 21 + .../toolchain/binutils/2.22/999-ppc-textrels.patch | 80 +++ misc/buildroot/toolchain/binutils/Config.in | 5 + .../gcc/4.6.3/305-libmudflap-susv3-legacy.patch | 49 ++ .../gcc/4.6.3/810-arm-softfloat-libgcc.patch | 38 ++ .../gcc/4.6.3/820-arm-unbreak-armv4t.patch | 14 + .../toolchain/gcc/4.6.3/900-nuttx-nolibstdc.patch | 13 + .../powerpc-link-with-math-lib.patch.conditional | 125 ++++ misc/buildroot/toolchain/gcc/Config.in | 6 + misc/buildroot/toolchain/gdb/Config.in | 5 + misc/buildroot/toolchain/gdb/gdb.mk | 2 + nuttx/Documentation/NuttX.html | 34 +- nuttx/Documentation/NuttXLinks.html | 1 + nuttx/Documentation/NuttXNxFlat.html | 4 +- nuttx/Documentation/NuttXRelated.html | 2 +- nuttx/Documentation/NuttxPortingGuide.html | 18 +- nuttx/Documentation/UsbTrace.html | 664 ++++++++++----------- nuttx/configs/Kconfig | 26 +- nuttx/configs/README.txt | 24 +- nuttx/configs/amber/hello/Make.defs | 2 +- nuttx/configs/c5471evm/httpd/Make.defs | 2 +- nuttx/configs/c5471evm/nettest/Make.defs | 2 +- nuttx/configs/c5471evm/nsh/Make.defs | 2 +- nuttx/configs/c5471evm/ostest/Make.defs | 2 +- nuttx/configs/compal_e88/nsh_highram/Make.defs | 2 +- nuttx/configs/compal_e99/nsh_compalram/Make.defs | 2 +- nuttx/configs/compal_e99/nsh_highram/Make.defs | 2 +- nuttx/configs/demo9s12ne64/ostest/Make.defs | 2 +- nuttx/configs/ea3131/README.txt | 2 +- nuttx/configs/ea3131/nsh/Make.defs | 2 +- nuttx/configs/ea3131/ostest/Make.defs | 2 +- nuttx/configs/ea3131/pgnsh/Make.defs | 2 +- nuttx/configs/ea3131/usbserial/Make.defs | 2 +- nuttx/configs/ea3131/usbstorage/Make.defs | 2 +- nuttx/configs/ea3152/README.txt | 2 +- nuttx/configs/ea3152/ostest/Make.defs | 2 +- nuttx/configs/eagle100/README.txt | 2 +- nuttx/configs/eagle100/httpd/Make.defs | 6 +- nuttx/configs/eagle100/nettest/Make.defs | 6 +- nuttx/configs/eagle100/nsh/Make.defs | 6 +- nuttx/configs/eagle100/nxflat/Make.defs | 6 +- nuttx/configs/eagle100/ostest/Make.defs | 6 +- nuttx/configs/eagle100/thttpd/Make.defs | 6 +- nuttx/configs/ekk-lm3s9b96/nsh/Make.defs | 4 +- nuttx/configs/ekk-lm3s9b96/ostest/Make.defs | 4 +- nuttx/configs/fire-stm32v2/nsh/Make.defs | 6 +- nuttx/configs/hymini-stm32v/buttons/Make.defs | 4 +- nuttx/configs/hymini-stm32v/nsh/Make.defs | 4 +- nuttx/configs/hymini-stm32v/nsh2/Make.defs | 4 +- nuttx/configs/hymini-stm32v/nx/Make.defs | 4 +- nuttx/configs/hymini-stm32v/nxlines/Make.defs | 4 +- nuttx/configs/hymini-stm32v/usbserial/Make.defs | 4 +- nuttx/configs/hymini-stm32v/usbstorage/Make.defs | 4 +- nuttx/configs/kwikstik-k40/ostest/Make.defs | 4 +- nuttx/configs/lincoln60/nsh/Make.defs | 4 +- nuttx/configs/lincoln60/ostest/Make.defs | 4 +- nuttx/configs/lm3s6432-s2e/nsh/Make.defs | 4 +- nuttx/configs/lm3s6432-s2e/ostest/Make.defs | 4 +- nuttx/configs/lm3s6965-ek/nsh/Make.defs | 4 +- nuttx/configs/lm3s6965-ek/nx/Make.defs | 4 +- nuttx/configs/lm3s6965-ek/ostest/Make.defs | 4 +- nuttx/configs/lm3s8962-ek/nsh/Make.defs | 4 +- nuttx/configs/lm3s8962-ek/nx/Make.defs | 4 +- nuttx/configs/lm3s8962-ek/ostest/Make.defs | 4 +- nuttx/configs/lpc4330-xplorer/nsh/Make.defs | 6 +- nuttx/configs/lpc4330-xplorer/ostest/Make.defs | 6 +- nuttx/configs/lpcxpresso-lpc1768/dhcpd/Make.defs | 4 +- nuttx/configs/lpcxpresso-lpc1768/nsh/Make.defs | 4 +- nuttx/configs/lpcxpresso-lpc1768/nx/Make.defs | 4 +- nuttx/configs/lpcxpresso-lpc1768/ostest/Make.defs | 4 +- nuttx/configs/lpcxpresso-lpc1768/thttpd/Make.defs | 4 +- .../lpcxpresso-lpc1768/usbstorage/Make.defs | 4 +- nuttx/configs/m68332evb/Make.defs | 2 +- nuttx/configs/m68332evb/doc/m68k-defconfig | 2 +- nuttx/configs/mbed/hidkbd/Make.defs | 4 +- nuttx/configs/mbed/nsh/Make.defs | 4 +- nuttx/configs/mcu123-lpc214x/README.txt | 2 +- nuttx/configs/mcu123-lpc214x/composite/Make.defs | 6 +- nuttx/configs/mcu123-lpc214x/nsh/Make.defs | 8 +- nuttx/configs/mcu123-lpc214x/ostest/Make.defs | 8 +- nuttx/configs/mcu123-lpc214x/usbserial/Make.defs | 8 +- nuttx/configs/mcu123-lpc214x/usbstorage/Make.defs | 8 +- nuttx/configs/micropendous3/README.txt | 2 +- nuttx/configs/micropendous3/hello/Make.defs | 2 +- nuttx/configs/mx1ads/ostest/Make.defs | 2 +- nuttx/configs/ne64badge/ostest/Make.defs | 2 +- nuttx/configs/ntosd-dm320/nettest/Make.defs | 2 +- nuttx/configs/ntosd-dm320/nsh/Make.defs | 2 +- nuttx/configs/ntosd-dm320/ostest/Make.defs | 2 +- nuttx/configs/ntosd-dm320/poll/Make.defs | 2 +- nuttx/configs/ntosd-dm320/thttpd/Make.defs | 2 +- nuttx/configs/ntosd-dm320/udp/Make.defs | 2 +- nuttx/configs/ntosd-dm320/uip/Make.defs | 2 +- nuttx/configs/nucleus2g/nsh/Make.defs | 4 +- nuttx/configs/nucleus2g/ostest/Make.defs | 4 +- nuttx/configs/nucleus2g/usbserial/Make.defs | 4 +- nuttx/configs/nucleus2g/usbstorage/Make.defs | 4 +- nuttx/configs/olimex-lpc1766stk/README.txt | 2 +- nuttx/configs/olimex-lpc1766stk/ftpc/Make.defs | 4 +- nuttx/configs/olimex-lpc1766stk/hidkbd/Make.defs | 4 +- nuttx/configs/olimex-lpc1766stk/nettest/Make.defs | 4 +- nuttx/configs/olimex-lpc1766stk/nsh/Make.defs | 4 +- nuttx/configs/olimex-lpc1766stk/nx/Make.defs | 4 +- nuttx/configs/olimex-lpc1766stk/ostest/Make.defs | 4 +- .../configs/olimex-lpc1766stk/slip-httpd/Make.defs | 4 +- nuttx/configs/olimex-lpc1766stk/thttpd/Make.defs | 4 +- .../configs/olimex-lpc1766stk/usbserial/Make.defs | 4 +- .../configs/olimex-lpc1766stk/usbstorage/Make.defs | 4 +- nuttx/configs/olimex-lpc1766stk/wlan/Make.defs | 4 +- nuttx/configs/olimex-lpc2378/nsh/Make.defs | 4 +- nuttx/configs/olimex-lpc2378/ostest/Make.defs | 4 +- nuttx/configs/olimex-stm32-p107/nsh/Make.defs | 4 +- nuttx/configs/olimex-stm32-p107/ostest/Make.defs | 4 +- nuttx/configs/olimex-strp711/README.txt | 6 +- nuttx/configs/olimex-strp711/nettest/Make.defs | 8 +- nuttx/configs/olimex-strp711/nsh/Make.defs | 8 +- nuttx/configs/olimex-strp711/ostest/Make.defs | 8 +- nuttx/configs/qemu-i486/nsh/Make.defs | 2 +- nuttx/configs/qemu-i486/ostest/Make.defs | 2 +- nuttx/configs/sam3u-ek/knsh/Make.defs | 4 +- nuttx/configs/sam3u-ek/nsh/Make.defs | 4 +- nuttx/configs/sam3u-ek/nx/Make.defs | 4 +- nuttx/configs/sam3u-ek/ostest/Make.defs | 4 +- nuttx/configs/sam3u-ek/touchscreen/Make.defs | 4 +- nuttx/configs/shenzhou/nsh/Make.defs | 6 +- nuttx/configs/shenzhou/nxwm/Make.defs | 6 +- nuttx/configs/skp16c26/README.txt | 224 +++---- nuttx/configs/skp16c26/ostest/Make.defs | 2 +- nuttx/configs/stm3210e-eval/RIDE/Make.defs | 4 +- nuttx/configs/stm3210e-eval/buttons/Make.defs | 4 +- nuttx/configs/stm3210e-eval/composite/Make.defs | 4 +- nuttx/configs/stm3210e-eval/nsh/Make.defs | 4 +- nuttx/configs/stm3210e-eval/nsh2/Make.defs | 4 +- nuttx/configs/stm3210e-eval/nx/Make.defs | 4 +- nuttx/configs/stm3210e-eval/nxconsole/Make.defs | 4 +- nuttx/configs/stm3210e-eval/nxlines/Make.defs | 4 +- nuttx/configs/stm3210e-eval/nxtext/Make.defs | 4 +- nuttx/configs/stm3210e-eval/ostest/Make.defs | 4 +- nuttx/configs/stm3210e-eval/pm/Make.defs | 4 +- nuttx/configs/stm3210e-eval/usbserial/Make.defs | 4 +- nuttx/configs/stm3210e-eval/usbstorage/Make.defs | 4 +- nuttx/configs/stm3220g-eval/dhcpd/Make.defs | 6 +- nuttx/configs/stm3220g-eval/nettest/Make.defs | 6 +- nuttx/configs/stm3220g-eval/nsh/Make.defs | 6 +- nuttx/configs/stm3220g-eval/nsh2/Make.defs | 6 +- nuttx/configs/stm3220g-eval/nxwm/Make.defs | 6 +- nuttx/configs/stm3220g-eval/ostest/Make.defs | 6 +- nuttx/configs/stm3220g-eval/telnetd/Make.defs | 6 +- nuttx/configs/stm3240g-eval/dhcpd/Make.defs | 6 +- nuttx/configs/stm3240g-eval/discover/Make.defs | 6 +- nuttx/configs/stm3240g-eval/nettest/Make.defs | 6 +- nuttx/configs/stm3240g-eval/nsh/Make.defs | 6 +- nuttx/configs/stm3240g-eval/nsh2/Make.defs | 6 +- nuttx/configs/stm3240g-eval/nxconsole/Make.defs | 6 +- nuttx/configs/stm3240g-eval/nxwm/Make.defs | 6 +- nuttx/configs/stm3240g-eval/ostest/Make.defs | 6 +- nuttx/configs/stm3240g-eval/telnetd/Make.defs | 6 +- nuttx/configs/stm3240g-eval/webserver/Make.defs | 6 +- nuttx/configs/stm3240g-eval/xmlrpc/Make.defs | 6 +- nuttx/configs/stm32f4discovery/nsh/Make.defs | 6 +- nuttx/configs/stm32f4discovery/nxlines/Make.defs | 6 +- nuttx/configs/stm32f4discovery/ostest/Make.defs | 6 +- nuttx/configs/stm32f4discovery/pm/Make.defs | 6 +- nuttx/configs/teensy/hello/Make.defs | 2 +- nuttx/configs/teensy/nsh/Make.defs | 2 +- nuttx/configs/teensy/usbstorage/Make.defs | 2 +- nuttx/configs/twr-k60n512/nsh/Make.defs | 4 +- nuttx/configs/twr-k60n512/ostest/Make.defs | 4 +- nuttx/configs/us7032evb1/nsh/Make.defs | 2 +- nuttx/configs/us7032evb1/ostest/Make.defs | 2 +- nuttx/configs/vsn/nsh/Make.defs | 4 +- 199 files changed, 1372 insertions(+), 833 deletions(-) create mode 100644 misc/buildroot/configs/cortexm3-eabi-defconfig-4.6.3 create mode 100755 misc/buildroot/toolchain/binutils/2.22/120-sh-conf.patch create mode 100755 misc/buildroot/toolchain/binutils/2.22/300-001_ld_makefile_patch.patch create mode 100755 misc/buildroot/toolchain/binutils/2.22/300-012_check_ldrunpath_length.patch create mode 100755 misc/buildroot/toolchain/binutils/2.22/999-ppc-textrels.patch create mode 100755 misc/buildroot/toolchain/gcc/4.6.3/305-libmudflap-susv3-legacy.patch create mode 100755 misc/buildroot/toolchain/gcc/4.6.3/810-arm-softfloat-libgcc.patch create mode 100755 misc/buildroot/toolchain/gcc/4.6.3/820-arm-unbreak-armv4t.patch create mode 100755 misc/buildroot/toolchain/gcc/4.6.3/900-nuttx-nolibstdc.patch create mode 100755 misc/buildroot/toolchain/gcc/4.6.3/powerpc-link-with-math-lib.patch.conditional (limited to 'nuttx') diff --git a/misc/buildroot/ChangeLog b/misc/buildroot/ChangeLog index 9c22edf03..0d896872f 100644 --- a/misc/buildroot/ChangeLog +++ b/misc/buildroot/ChangeLog @@ -115,5 +115,8 @@ buildroot-1.11 2011-xx-xx - there is some assembler error when compiling gcc for arm, gcc bugzilla 43999 - you can't build nuttx for cortex m3/m4 because of a missing instruction - in ethe assembler, binutils bugzilla 12296 + in the assembler, binutils bugzilla 12296 + * Add support for binutils 2.22 and GCC 4.6.3. + * Change name of all tools from xxx-elf to xxx-nuttx-elf + * Added an ARM EABI GCC 4.6.3 configuration (tool name is arm-nuttx-eabi-). diff --git a/misc/buildroot/Config.in b/misc/buildroot/Config.in index d5c5fbfe7..fe33b158d 100644 --- a/misc/buildroot/Config.in +++ b/misc/buildroot/Config.in @@ -343,7 +343,8 @@ config BR2_GNU_BUILD_SUFFIX config BR2_GNU_TARGET_SUFFIX string "GNU target suffix" - default "elf" + default "nuttx-elf" if !BR2_ARM_EABI + default "nuttx-eabi" if BR2_ARM_EABI help The string used to pass to configure scripts via the --target= option. Just specify the suffix here, the leading diff --git a/misc/buildroot/configs/arm-defconfig b/misc/buildroot/configs/arm-defconfig index bcdab8c89..81a8508fe 100644 --- a/misc/buildroot/configs/arm-defconfig +++ b/misc/buildroot/configs/arm-defconfig @@ -58,7 +58,7 @@ BR2_NUTTX_DIR="$(TOPDIR)/../../nuttx" BR2_TOPDIR_PREFIX="" BR2_TOPDIR_SUFFIX="" BR2_GNU_BUILD_SUFFIX="pc-elf" -BR2_GNU_TARGET_SUFFIX="elf" +BR2_GNU_TARGET_SUFFIX="nuttx-elf" # BR2_PREFER_IMA is not set # diff --git a/misc/buildroot/configs/arm7tdmi-defconfig-4.2.4 b/misc/buildroot/configs/arm7tdmi-defconfig-4.2.4 index 00f05bc9c..093cc1667 100644 --- a/misc/buildroot/configs/arm7tdmi-defconfig-4.2.4 +++ b/misc/buildroot/configs/arm7tdmi-defconfig-4.2.4 @@ -60,7 +60,7 @@ BR2_NUTTX_DIR="$(TOPDIR)/../../nuttx" BR2_TOPDIR_PREFIX="" BR2_TOPDIR_SUFFIX="" BR2_GNU_BUILD_SUFFIX="pc-elf" -BR2_GNU_TARGET_SUFFIX="elf" +BR2_GNU_TARGET_SUFFIX="nuttx-elf" # BR2_PREFER_IMA is not set # diff --git a/misc/buildroot/configs/arm7tdmi-defconfig-4.3.3 b/misc/buildroot/configs/arm7tdmi-defconfig-4.3.3 index 9207ad3e2..7e97a77d6 100644 --- a/misc/buildroot/configs/arm7tdmi-defconfig-4.3.3 +++ b/misc/buildroot/configs/arm7tdmi-defconfig-4.3.3 @@ -60,7 +60,7 @@ BR2_NUTTX_DIR="$(TOPDIR)/../../nuttx" BR2_TOPDIR_PREFIX="" BR2_TOPDIR_SUFFIX="" BR2_GNU_BUILD_SUFFIX="pc-elf" -BR2_GNU_TARGET_SUFFIX="elf" +BR2_GNU_TARGET_SUFFIX="nuttx-elf" # BR2_PREFER_IMA is not set # diff --git a/misc/buildroot/configs/arm920t-defconfig-4.2.4 b/misc/buildroot/configs/arm920t-defconfig-4.2.4 index 4abf36813..ae933fcec 100644 --- a/misc/buildroot/configs/arm920t-defconfig-4.2.4 +++ b/misc/buildroot/configs/arm920t-defconfig-4.2.4 @@ -60,7 +60,7 @@ BR2_NUTTX_DIR="$(TOPDIR)/../../nuttx" BR2_TOPDIR_PREFIX="" BR2_TOPDIR_SUFFIX="" BR2_GNU_BUILD_SUFFIX="pc-elf" -BR2_GNU_TARGET_SUFFIX="elf" +BR2_GNU_TARGET_SUFFIX="nuttx-elf" # BR2_PREFER_IMA is not set # diff --git a/misc/buildroot/configs/arm920t-defconfig-4.3.3 b/misc/buildroot/configs/arm920t-defconfig-4.3.3 index f6080a03c..7f9f6b03f 100644 --- a/misc/buildroot/configs/arm920t-defconfig-4.3.3 +++ b/misc/buildroot/configs/arm920t-defconfig-4.3.3 @@ -61,7 +61,7 @@ BR2_NUTTX_DIR="$(TOPDIR)/../../nuttx" BR2_TOPDIR_PREFIX="" BR2_TOPDIR_SUFFIX="" BR2_GNU_BUILD_SUFFIX="pc-elf" -BR2_GNU_TARGET_SUFFIX="elf" +BR2_GNU_TARGET_SUFFIX="nuttx-elf" # BR2_PREFER_IMA is not set # diff --git a/misc/buildroot/configs/arm926t-defconfig-4.2.4 b/misc/buildroot/configs/arm926t-defconfig-4.2.4 index 1c5ae784d..26b266f0e 100644 --- a/misc/buildroot/configs/arm926t-defconfig-4.2.4 +++ b/misc/buildroot/configs/arm926t-defconfig-4.2.4 @@ -60,7 +60,7 @@ BR2_NUTTX_DIR="$(TOPDIR)/../../nuttx" BR2_TOPDIR_PREFIX="" BR2_TOPDIR_SUFFIX="" BR2_GNU_BUILD_SUFFIX="pc-elf" -BR2_GNU_TARGET_SUFFIX="elf" +BR2_GNU_TARGET_SUFFIX="nuttx-elf" # BR2_PREFER_IMA is not set # diff --git a/misc/buildroot/configs/arm926t-defconfig-4.3.3 b/misc/buildroot/configs/arm926t-defconfig-4.3.3 index 3d3d7d9f7..b72a12451 100644 --- a/misc/buildroot/configs/arm926t-defconfig-4.3.3 +++ b/misc/buildroot/configs/arm926t-defconfig-4.3.3 @@ -60,7 +60,7 @@ BR2_NUTTX_DIR="$(TOPDIR)/../../nuttx" BR2_TOPDIR_PREFIX="" BR2_TOPDIR_SUFFIX="" BR2_GNU_BUILD_SUFFIX="arm-elf" -BR2_GNU_TARGET_SUFFIX="elf" +BR2_GNU_TARGET_SUFFIX="nuttx-elf" # BR2_PREFER_IMA is not set # BR2_DEPRECATED is not set diff --git a/misc/buildroot/configs/arm926t-defconfig-nxflat b/misc/buildroot/configs/arm926t-defconfig-nxflat index f0ddd17bc..d449ef4ab 100644 --- a/misc/buildroot/configs/arm926t-defconfig-nxflat +++ b/misc/buildroot/configs/arm926t-defconfig-nxflat @@ -60,7 +60,7 @@ BR2_NUTTX_DIR="$(TOPDIR)/../../nuttx" BR2_TOPDIR_PREFIX="" BR2_TOPDIR_SUFFIX="" BR2_GNU_BUILD_SUFFIX="arm-elf" -BR2_GNU_TARGET_SUFFIX="elf" +BR2_GNU_TARGET_SUFFIX="nuttx-elf" # BR2_PREFER_IMA is not set # BR2_DEPRECATED is not set diff --git a/misc/buildroot/configs/avr-defconfig-4.3.3 b/misc/buildroot/configs/avr-defconfig-4.3.3 index a597e5e3b..a2ea9feb1 100644 --- a/misc/buildroot/configs/avr-defconfig-4.3.3 +++ b/misc/buildroot/configs/avr-defconfig-4.3.3 @@ -41,7 +41,7 @@ BR2_NUTTX_DIR="$(TOPDIR)/../../nuttx" BR2_TOPDIR_PREFIX="" BR2_TOPDIR_SUFFIX="" BR2_GNU_BUILD_SUFFIX="pc-elf" -BR2_GNU_TARGET_SUFFIX="elf" +BR2_GNU_TARGET_SUFFIX="nuttx-elf" # BR2_PREFER_IMA is not set # diff --git a/misc/buildroot/configs/avr-defconfig-4.5.2 b/misc/buildroot/configs/avr-defconfig-4.5.2 index e0ebe0559..465376fd0 100644 --- a/misc/buildroot/configs/avr-defconfig-4.5.2 +++ b/misc/buildroot/configs/avr-defconfig-4.5.2 @@ -41,7 +41,7 @@ BR2_NUTTX_DIR="$(TOPDIR)/../../nuttx" BR2_TOPDIR_PREFIX="" BR2_TOPDIR_SUFFIX="" BR2_GNU_BUILD_SUFFIX="pc-elf" -BR2_GNU_TARGET_SUFFIX="elf" +BR2_GNU_TARGET_SUFFIX="nuttx-elf" # BR2_PREFER_IMA is not set # diff --git a/misc/buildroot/configs/bfin-defconfig-4.2.4 b/misc/buildroot/configs/bfin-defconfig-4.2.4 index a88b9f269..9cae0a8d9 100644 --- a/misc/buildroot/configs/bfin-defconfig-4.2.4 +++ b/misc/buildroot/configs/bfin-defconfig-4.2.4 @@ -40,7 +40,7 @@ BR2_NUTTX_DIR="$(TOPDIR)/../../nuttx" BR2_TOPDIR_PREFIX="" BR2_TOPDIR_SUFFIX="" BR2_GNU_BUILD_SUFFIX="pc-elf" -BR2_GNU_TARGET_SUFFIX="elf" +BR2_GNU_TARGET_SUFFIX="nuttx-elf" # BR2_PREFER_IMA is not set # diff --git a/misc/buildroot/configs/cortexm3-defconfig-4.3.3 b/misc/buildroot/configs/cortexm3-defconfig-4.3.3 index 36a441c69..664000a16 100644 --- a/misc/buildroot/configs/cortexm3-defconfig-4.3.3 +++ b/misc/buildroot/configs/cortexm3-defconfig-4.3.3 @@ -60,7 +60,7 @@ BR2_NUTTX_DIR="$(TOPDIR)/../../nuttx" BR2_TOPDIR_PREFIX="" BR2_TOPDIR_SUFFIX="" BR2_GNU_BUILD_SUFFIX="pc-elf" -BR2_GNU_TARGET_SUFFIX="elf" +BR2_GNU_TARGET_SUFFIX="nuttx-elf" # BR2_PREFER_IMA is not set # diff --git a/misc/buildroot/configs/cortexm3-defconfig-nxflat b/misc/buildroot/configs/cortexm3-defconfig-nxflat index ac247703a..263126d1f 100644 --- a/misc/buildroot/configs/cortexm3-defconfig-nxflat +++ b/misc/buildroot/configs/cortexm3-defconfig-nxflat @@ -60,7 +60,7 @@ BR2_NUTTX_DIR="$(TOPDIR)/../../nuttx" BR2_TOPDIR_PREFIX="" BR2_TOPDIR_SUFFIX="" BR2_GNU_BUILD_SUFFIX="pc-elf" -BR2_GNU_TARGET_SUFFIX="elf" +BR2_GNU_TARGET_SUFFIX="nuttx-elf" # BR2_PREFER_IMA is not set # diff --git a/misc/buildroot/configs/cortexm3-eabi-defconfig-4.6.3 b/misc/buildroot/configs/cortexm3-eabi-defconfig-4.6.3 new file mode 100644 index 000000000..7839f667b --- /dev/null +++ b/misc/buildroot/configs/cortexm3-eabi-defconfig-4.6.3 @@ -0,0 +1,123 @@ +# +# Automatically generated make config: don't edit +# +BR2_HAVE_DOT_CONFIG=y +# BR2_alpha is not set +BR2_arm=y +# BR2_armeb is not set +# BR2_avr is not set +# BR2_avr32 is not set +# BR2_bfin is not set +# BR2_cris is not set +# BR2_i386 is not set +# BR2_m32c is not set +# BR2_m68k is not set +# BR2_m68hc11 is not set +# BR2_m68hc12 is not set +# BR2_m9s12x is not set +# BR2_mips is not set +# BR2_mipsel is not set +# BR2_nios2 is not set +# BR2_powerpc is not set +# BR2_sh is not set +# BR2_sh64 is not set +# BR2_h8300 is not set +# BR2_sparc is not set +# BR2_x86_64 is not set +# BR2_generic_arm is not set +# BR2_arm610 is not set +# BR2_arm7tdmi is not set +# BR2_arm710 is not set +# BR2_arm720t is not set +# BR2_arm740t is not set +# BR2_arm920t is not set +# BR2_arm922t is not set +# BR2_arm926t is not set +# BR2_arm1136jf_s is not set +BR2_cortex_m3=y +# BR2_sa110 is not set +# BR2_sa1100 is not set +# BR2_xscale is not set +# BR2_iwmmxt is not set +# BR2_ARM_OABI is not set +BR2_ARM_EABI=y +BR2_ARCH="arm" +BR2_GCC_TARGET_TUNE="cortex-m3" +BR2_GCC_TARGET_ARCH="armv7-m" +BR2_GCC_TARGET_ABI="aapcs-linux" +BR2_ENDIAN="LITTLE" + +# +# Build options +# +BR2_WGET="wget --passive-ftp" +BR2_SVN="svn co" +BR2_ZCAT="zcat" +BR2_BZCAT="bzcat" +BR2_TAR_OPTIONS="" +BR2_DL_DIR="$(BASE_DIR)/../archives" +BR2_STAGING_DIR="$(BUILD_DIR)/staging_dir" +BR2_NUTTX_DIR="$(TOPDIR)/../../nuttx" +BR2_TOPDIR_PREFIX="" +BR2_TOPDIR_SUFFIX="" +BR2_GNU_BUILD_SUFFIX="pc-elf" +BR2_GNU_TARGET_SUFFIX="nuttx-eabi" +# BR2_PREFER_IMA is not set + +# +# Toolchain Options +# + +# +# Binutils Options +# +# BR2_BINUTILS_VERSION_2_17 is not set +# BR2_BINUTILS_VERSION_2_18 is not set +# BR2_BINUTILS_VERSION_2_19 is not set +# BR2_BINUTILS_VERSION_2_19_1 is not set +# BR2_BINUTILS_VERSION_2_21_1 is not set +BR2_BINUTILS_VERSION_2_22=y +BR2_BINUTILS_VERSION="2.22" +BR2_EXTRA_BINUTILS_CONFIG_OPTIONS="" + +# +# GCC Options +# +BR2_PACKAGE_GCC=y +# BR2_GCC_VERSION_3_3_6 is not set +# BR2_GCC_VERSION_3_4_6 is not set +# BR2_GCC_VERSION_4_2_4 is not set +# BR2_GCC_VERSION_4_3_3 is not set +# BR2_GCC_VERSION_4_5_2 is not set +BR2_GCC_VERSION_4_6_3=y +BR2_GCC_SUPPORTS_SYSROOT=y +BR2_GCC_VERSION="4.6.3" +# BR2_GCC_USE_SJLJ_EXCEPTIONS is not set +BR2_EXTRA_GCC_CONFIG_OPTIONS="" +BR2_INSTALL_LIBSTDCPP=y +# BR2_INSTALL_LIBGCJ is not set +# BR2_INSTALL_OBJC is not set +# BR2_INSTALL_FORTRAN is not set + +# +# Gdb Options +# +# BR2_PACKAGE_GDB is not set +# BR2_PACKAGE_GDB_SERVER is not set +# BR2_PACKAGE_GDB_HOST is not set + +# +# NuttX Binary Support +# +BR2_PACKAGE_NXFLAT=y +BR2_PACKAGE_GENROMFS=y + +# +# Common Toolchain Options +# +# BR2_PACKAGE_SSTRIP_TARGET is not set +# BR2_PACKAGE_SSTRIP_HOST is not set +# BR2_ENABLE_MULTILIB is not set +BR2_LARGEFILE=y +BR2_SOFT_FLOAT=y +BR2_TARGET_OPTIMIZATION="-Os -pipe" diff --git a/misc/buildroot/configs/h8300_defconfig b/misc/buildroot/configs/h8300_defconfig index 127b04de3..df7e91b10 100644 --- a/misc/buildroot/configs/h8300_defconfig +++ b/misc/buildroot/configs/h8300_defconfig @@ -40,7 +40,7 @@ BR2_NUTTX_DIR="$(TOPDIR)/../../nuttx" BR2_TOPDIR_PREFIX="" BR2_TOPDIR_SUFFIX="" BR2_GNU_BUILD_SUFFIX="pc-elf" -BR2_GNU_TARGET_SUFFIX="elf" +BR2_GNU_TARGET_SUFFIX="nuttx-elf" # BR2_PREFER_IMA is not set # diff --git a/misc/buildroot/configs/i486-defconfig-4.3.3 b/misc/buildroot/configs/i486-defconfig-4.3.3 index c99130521..ca79c8518 100644 --- a/misc/buildroot/configs/i486-defconfig-4.3.3 +++ b/misc/buildroot/configs/i486-defconfig-4.3.3 @@ -47,7 +47,7 @@ BR2_NUTTX_DIR="$(TOPDIR)/../../nuttx" BR2_TOPDIR_PREFIX="" BR2_TOPDIR_SUFFIX="" BR2_GNU_BUILD_SUFFIX="pc-elf" -BR2_GNU_TARGET_SUFFIX="elf" +BR2_GNU_TARGET_SUFFIX="nuttx-elf" # BR2_PREFER_IMA is not set # diff --git a/misc/buildroot/configs/m32c-defconfig-4.2.4 b/misc/buildroot/configs/m32c-defconfig-4.2.4 index cf6b51bde..2942cf830 100644 --- a/misc/buildroot/configs/m32c-defconfig-4.2.4 +++ b/misc/buildroot/configs/m32c-defconfig-4.2.4 @@ -40,7 +40,7 @@ BR2_NUTTX_DIR="$(TOPDIR)/../../nuttx" BR2_TOPDIR_PREFIX="" BR2_TOPDIR_SUFFIX="" BR2_GNU_BUILD_SUFFIX="pc-elf" -BR2_GNU_TARGET_SUFFIX="elf" +BR2_GNU_TARGET_SUFFIX="nuttx-elf" # BR2_PREFER_IMA is not set # diff --git a/misc/buildroot/configs/m32c-defconfig-4.3.3 b/misc/buildroot/configs/m32c-defconfig-4.3.3 index ef7fa4d00..35f307b75 100644 --- a/misc/buildroot/configs/m32c-defconfig-4.3.3 +++ b/misc/buildroot/configs/m32c-defconfig-4.3.3 @@ -40,7 +40,7 @@ BR2_NUTTX_DIR="$(TOPDIR)/../../nuttx" BR2_TOPDIR_PREFIX="" BR2_TOPDIR_SUFFIX="" BR2_GNU_BUILD_SUFFIX="pc-elf" -BR2_GNU_TARGET_SUFFIX="elf" +BR2_GNU_TARGET_SUFFIX="nuttx-elf" # BR2_PREFER_IMA is not set # diff --git a/misc/buildroot/configs/m68hc11-config b/misc/buildroot/configs/m68hc11-config index 9496beb66..5d546f146 100644 --- a/misc/buildroot/configs/m68hc11-config +++ b/misc/buildroot/configs/m68hc11-config @@ -40,7 +40,7 @@ BR2_NUTTX_DIR="$(TOPDIR)/../../nuttx" BR2_TOPDIR_PREFIX="" BR2_TOPDIR_SUFFIX="" BR2_GNU_BUILD_SUFFIX="pc-elf" -BR2_GNU_TARGET_SUFFIX="elf" +BR2_GNU_TARGET_SUFFIX="nuttx-elf" # BR2_PREFER_IMA is not set # diff --git a/misc/buildroot/configs/m68hc12-config-3.4.6 b/misc/buildroot/configs/m68hc12-config-3.4.6 index 3277e0989..eb2dca5f0 100644 --- a/misc/buildroot/configs/m68hc12-config-3.4.6 +++ b/misc/buildroot/configs/m68hc12-config-3.4.6 @@ -40,7 +40,7 @@ BR2_NUTTX_DIR="$(TOPDIR)/../../nuttx" BR2_TOPDIR_PREFIX="" BR2_TOPDIR_SUFFIX="" BR2_GNU_BUILD_SUFFIX="pc-elf" -BR2_GNU_TARGET_SUFFIX="elf" +BR2_GNU_TARGET_SUFFIX="nuttx-elf" # BR2_PREFER_IMA is not set # diff --git a/misc/buildroot/configs/m68hc12-config-4.3.3 b/misc/buildroot/configs/m68hc12-config-4.3.3 index e889e273d..300194f36 100644 --- a/misc/buildroot/configs/m68hc12-config-4.3.3 +++ b/misc/buildroot/configs/m68hc12-config-4.3.3 @@ -40,7 +40,7 @@ BR2_NUTTX_DIR="$(TOPDIR)/../../nuttx" BR2_TOPDIR_PREFIX="" BR2_TOPDIR_SUFFIX="" BR2_GNU_BUILD_SUFFIX="pc-elf" -BR2_GNU_TARGET_SUFFIX="elf" +BR2_GNU_TARGET_SUFFIX="nuttx-elf" # BR2_PREFER_IMA is not set # diff --git a/misc/buildroot/configs/m68k-defconfig b/misc/buildroot/configs/m68k-defconfig index 2de720755..33b978633 100644 --- a/misc/buildroot/configs/m68k-defconfig +++ b/misc/buildroot/configs/m68k-defconfig @@ -40,7 +40,7 @@ BR2_NUTTX_DIR="$(TOPDIR)/../../nuttx" BR2_TOPDIR_PREFIX="" BR2_TOPDIR_SUFFIX="" BR2_GNU_BUILD_SUFFIX="pc-elf" -BR2_GNU_TARGET_SUFFIX="elf" +BR2_GNU_TARGET_SUFFIX="nuttx-elf" # BR2_PREFER_IMA is not set # diff --git a/misc/buildroot/configs/m9s12x-config-3.3.6 b/misc/buildroot/configs/m9s12x-config-3.3.6 index ab75d010d..d317ee7d8 100644 --- a/misc/buildroot/configs/m9s12x-config-3.3.6 +++ b/misc/buildroot/configs/m9s12x-config-3.3.6 @@ -41,7 +41,7 @@ BR2_NUTTX_DIR="$(TOPDIR)/../../nuttx" BR2_TOPDIR_PREFIX="" BR2_TOPDIR_SUFFIX="" BR2_GNU_BUILD_SUFFIX="pc-elf" -BR2_GNU_TARGET_SUFFIX="elf" +BR2_GNU_TARGET_SUFFIX="nuttx-elf" # BR2_PREFER_IMA is not set # diff --git a/misc/buildroot/configs/sh-defconfig b/misc/buildroot/configs/sh-defconfig index 5fc95a5ff..1700faf24 100644 --- a/misc/buildroot/configs/sh-defconfig +++ b/misc/buildroot/configs/sh-defconfig @@ -47,7 +47,7 @@ BR2_NUTTX_DIR="$(TOPDIR)/../../nuttx" BR2_TOPDIR_PREFIX="" BR2_TOPDIR_SUFFIX="" BR2_GNU_BUILD_SUFFIX="pc-elf" -BR2_GNU_TARGET_SUFFIX="elf" +BR2_GNU_TARGET_SUFFIX="nuttx-elf" # BR2_PREFER_IMA is not set # diff --git a/misc/buildroot/toolchain/binutils/2.22/120-sh-conf.patch b/misc/buildroot/toolchain/binutils/2.22/120-sh-conf.patch new file mode 100755 index 000000000..ea3d1b606 --- /dev/null +++ b/misc/buildroot/toolchain/binutils/2.22/120-sh-conf.patch @@ -0,0 +1,29 @@ +r10231 | lethal | 2005-05-02 09:58:00 -0400 (Mon, 02 May 2005) | 13 lines + +Likewise, binutils has no idea about any of these new targets either, so we +fix that up too.. now we're able to actually build a real toolchain for +sh2a_nofpu- and other more ineptly named toolchains (and yes, there are more +inept targets than that one, really. Go look, I promise). + +--- a/configure ++++ b/configure +@@ -1495,7 +1495,7 @@ + mips*-*-*) + noconfigdirs="$noconfigdirs gprof" + ;; +- sh-*-* | sh64-*-*) ++ sh*-*-* | sh64-*-*) + case "${target}" in + sh*-*-elf) + ;; +--- a/configure.ac ++++ b/configure.ac +@@ -712,7 +712,7 @@ + mips*-*-*) + noconfigdirs="$noconfigdirs gprof" + ;; +- sh-*-* | sh64-*-*) ++ sh*-*-* | sh64-*-*) + case "${target}" in + sh*-*-elf) + ;; diff --git a/misc/buildroot/toolchain/binutils/2.22/300-001_ld_makefile_patch.patch b/misc/buildroot/toolchain/binutils/2.22/300-001_ld_makefile_patch.patch new file mode 100755 index 000000000..5cb0f614d --- /dev/null +++ b/misc/buildroot/toolchain/binutils/2.22/300-001_ld_makefile_patch.patch @@ -0,0 +1,24 @@ +diff -u binutils-2.17.50.0.17.oorig/ld/Makefile.am binutils-2.17.50.0.17/ld/Makefile.am +--- binutils-2.17.50.0.17.oorig/ld/Makefile.am 2007-06-18 19:29:29.000000000 +0200 ++++ binutils-2.17.50.0.17/ld/Makefile.am 2007-06-25 10:00:36.000000000 +0200 +@@ -18,7 +18,7 @@ + # We put the scripts in the directory $(scriptdir)/ldscripts. + # We can't put the scripts in $(datadir) because the SEARCH_DIR + # directives need to be different for native and cross linkers. +-scriptdir = $(tooldir)/lib ++scriptdir = $(libdir) + + EMUL = @EMUL@ + EMULATION_OFILES = @EMULATION_OFILES@ +diff -u binutils-2.17.50.0.17.oorig/ld/Makefile.in binutils-2.17.50.0.17/ld/Makefile.in +--- binutils-2.17.50.0.17.oorig/ld/Makefile.in 2007-06-18 19:29:29.000000000 +0200 ++++ binutils-2.17.50.0.17/ld/Makefile.in 2007-06-25 10:00:36.000000000 +0200 +@@ -287,7 +287,7 @@ + # We put the scripts in the directory $(scriptdir)/ldscripts. + # We can't put the scripts in $(datadir) because the SEARCH_DIR + # directives need to be different for native and cross linkers. +-scriptdir = $(tooldir)/lib ++scriptdir = $(libdir) + BASEDIR = $(srcdir)/.. + BFDDIR = $(BASEDIR)/bfd + INCDIR = $(BASEDIR)/include diff --git a/misc/buildroot/toolchain/binutils/2.22/300-012_check_ldrunpath_length.patch b/misc/buildroot/toolchain/binutils/2.22/300-012_check_ldrunpath_length.patch new file mode 100755 index 000000000..df783109b --- /dev/null +++ b/misc/buildroot/toolchain/binutils/2.22/300-012_check_ldrunpath_length.patch @@ -0,0 +1,21 @@ +diff -Nura binutils-2.21.orig/ld/emultempl/elf32.em binutils-2.21/ld/emultempl/elf32.em +--- binutils-2.21.orig/ld/emultempl/elf32.em 2010-10-29 09:10:36.000000000 -0300 ++++ binutils-2.21/ld/emultempl/elf32.em 2010-12-10 09:26:56.746102724 -0300 +@@ -1270,6 +1270,8 @@ + && command_line.rpath == NULL) + { + lib_path = (const char *) getenv ("LD_RUN_PATH"); ++ if ((lib_path) && (strlen (lib_path) == 0)) ++ lib_path = NULL; + if (gld${EMULATION_NAME}_search_needed (lib_path, &n, + force)) + break; +@@ -1497,6 +1499,8 @@ + rpath = command_line.rpath; + if (rpath == NULL) + rpath = (const char *) getenv ("LD_RUN_PATH"); ++ if ((rpath) && (strlen (rpath) == 0)) ++ rpath = NULL; + + for (abfd = link_info.input_bfds; abfd; abfd = abfd->link_next) + if (bfd_get_flavour (abfd) == bfd_target_elf_flavour) diff --git a/misc/buildroot/toolchain/binutils/2.22/999-ppc-textrels.patch b/misc/buildroot/toolchain/binutils/2.22/999-ppc-textrels.patch new file mode 100755 index 000000000..c1efacf24 --- /dev/null +++ b/misc/buildroot/toolchain/binutils/2.22/999-ppc-textrels.patch @@ -0,0 +1,80 @@ +http://bugs.gentoo.org/392645 +http://sourceware.org/bugzilla/show_bug.cgi?id=13470 + +2011-12-03 Alan Modra + + PR ld/13470 + * elf32-ppc.c (ppc_elf_copy_indirect_symbol): Revert substantive + change in 2011-07-01 commit. Comment. + * elf64-ppc.c (ppc64_elf_copy_indirect_symbol): Likewise. + +=================================================================== +RCS file: /cvs/src/src/bfd/elf32-ppc.c,v +retrieving revision 1.302.2.1 +retrieving revision 1.302.2.2 +diff -u -r1.302.2.1 -r1.302.2.2 +--- src/bfd/elf32-ppc.c 2011/11/15 11:36:52 1.302.2.1 ++++ src/bfd/elf32-ppc.c 2011/12/03 00:58:01 1.302.2.2 +@@ -2987,10 +2987,6 @@ + edir->elf.needs_plt |= eind->elf.needs_plt; + edir->elf.pointer_equality_needed |= eind->elf.pointer_equality_needed; + +- /* If we were called to copy over info for a weak sym, that's all. */ +- if (eind->elf.root.type != bfd_link_hash_indirect) +- return; +- + if (eind->dyn_relocs != NULL) + { + if (edir->dyn_relocs != NULL) +@@ -3022,6 +3018,16 @@ + eind->dyn_relocs = NULL; + } + ++ /* If we were called to copy over info for a weak sym, that's all. ++ You might think dyn_relocs need not be copied over; After all, ++ both syms will be dynamic or both non-dynamic so we're just ++ moving reloc accounting around. However, ELIMINATE_COPY_RELOCS ++ code in ppc_elf_adjust_dynamic_symbol needs to check for ++ dyn_relocs in read-only sections, and it does so on what is the ++ DIR sym here. */ ++ if (eind->elf.root.type != bfd_link_hash_indirect) ++ return; ++ + /* Copy over the GOT refcount entries that we may have already seen to + the symbol which just became indirect. */ + edir->elf.got.refcount += eind->elf.got.refcount; +=================================================================== +RCS file: /cvs/src/src/bfd/elf64-ppc.c,v +retrieving revision 1.363.2.4 +retrieving revision 1.363.2.5 +diff -u -r1.363.2.4 -r1.363.2.5 +--- src/bfd/elf64-ppc.c 2011/11/08 13:46:36 1.363.2.4 ++++ src/bfd/elf64-ppc.c 2011/12/03 00:58:02 1.363.2.5 +@@ -4435,10 +4435,6 @@ + edir->elf.ref_regular_nonweak |= eind->elf.ref_regular_nonweak; + edir->elf.needs_plt |= eind->elf.needs_plt; + +- /* If we were called to copy over info for a weak sym, that's all. */ +- if (eind->elf.root.type != bfd_link_hash_indirect) +- return; +- + /* Copy over any dynamic relocs we may have on the indirect sym. */ + if (eind->dyn_relocs != NULL) + { +@@ -4471,6 +4467,16 @@ + eind->dyn_relocs = NULL; + } + ++ /* If we were called to copy over info for a weak sym, that's all. ++ You might think dyn_relocs need not be copied over; After all, ++ both syms will be dynamic or both non-dynamic so we're just ++ moving reloc accounting around. However, ELIMINATE_COPY_RELOCS ++ code in ppc64_elf_adjust_dynamic_symbol needs to check for ++ dyn_relocs in read-only sections, and it does so on what is the ++ DIR sym here. */ ++ if (eind->elf.root.type != bfd_link_hash_indirect) ++ return; ++ + /* Copy over got entries that we may have already seen to the + symbol which just became indirect. */ + if (eind->elf.got.glist != NULL) diff --git a/misc/buildroot/toolchain/binutils/Config.in b/misc/buildroot/toolchain/binutils/Config.in index d1e674ba5..028ac0412 100644 --- a/misc/buildroot/toolchain/binutils/Config.in +++ b/misc/buildroot/toolchain/binutils/Config.in @@ -30,6 +30,10 @@ choice config BR2_BINUTILS_VERSION_2_21_1 depends !BR2_avr32 && !BR2_nios2 && !BR2_m9s12x bool "binutils 2.21.1" + + config BR2_BINUTILS_VERSION_2_22 + depends !BR2_avr32 && !BR2_nios2 && !BR2_m9s12x + bool "binutils 2.22" endchoice config BR2_BINUTILS_VERSION @@ -39,6 +43,7 @@ config BR2_BINUTILS_VERSION default "2.19" if BR2_BINUTILS_VERSION_2_19 default "2.19.1" if BR2_BINUTILS_VERSION_2_19_1 default "2.21.1" if BR2_BINUTILS_VERSION_2_21_1 + default "2.22" if BR2_BINUTILS_VERSION_2_22 config BR2_EXTRA_BINUTILS_CONFIG_OPTIONS string "Additional binutils options" diff --git a/misc/buildroot/toolchain/gcc/4.6.3/305-libmudflap-susv3-legacy.patch b/misc/buildroot/toolchain/gcc/4.6.3/305-libmudflap-susv3-legacy.patch new file mode 100755 index 000000000..374b1f865 --- /dev/null +++ b/misc/buildroot/toolchain/gcc/4.6.3/305-libmudflap-susv3-legacy.patch @@ -0,0 +1,49 @@ +Index: gcc-4.2/libmudflap/mf-hooks2.c +=================================================================== +--- gcc-4.2/libmudflap/mf-hooks2.c (revision 119834) ++++ gcc-4.2/libmudflap/mf-hooks2.c (working copy) +@@ -427,7 +427,7 @@ + { + TRACE ("%s\n", __PRETTY_FUNCTION__); + MF_VALIDATE_EXTENT(s, n, __MF_CHECK_WRITE, "bzero region"); +- bzero (s, n); ++ memset (s, 0, n); + } + + +@@ -437,7 +437,7 @@ + TRACE ("%s\n", __PRETTY_FUNCTION__); + MF_VALIDATE_EXTENT(src, n, __MF_CHECK_READ, "bcopy src"); + MF_VALIDATE_EXTENT(dest, n, __MF_CHECK_WRITE, "bcopy dest"); +- bcopy (src, dest, n); ++ memmove (dest, src, n); + } + + +@@ -447,7 +447,7 @@ + TRACE ("%s\n", __PRETTY_FUNCTION__); + MF_VALIDATE_EXTENT(s1, n, __MF_CHECK_READ, "bcmp 1st arg"); + MF_VALIDATE_EXTENT(s2, n, __MF_CHECK_READ, "bcmp 2nd arg"); +- return bcmp (s1, s2, n); ++ return n == 0 ? 0 : memcmp (s1, s2, n); + } + + +@@ -456,7 +456,7 @@ + size_t n = strlen (s); + TRACE ("%s\n", __PRETTY_FUNCTION__); + MF_VALIDATE_EXTENT(s, CLAMPADD(n, 1), __MF_CHECK_READ, "index region"); +- return index (s, c); ++ return strchr (s, c); + } + + +@@ -465,7 +465,7 @@ + size_t n = strlen (s); + TRACE ("%s\n", __PRETTY_FUNCTION__); + MF_VALIDATE_EXTENT(s, CLAMPADD(n, 1), __MF_CHECK_READ, "rindex region"); +- return rindex (s, c); ++ return strrchr (s, c); + } + + /* XXX: stpcpy, memccpy */ diff --git a/misc/buildroot/toolchain/gcc/4.6.3/810-arm-softfloat-libgcc.patch b/misc/buildroot/toolchain/gcc/4.6.3/810-arm-softfloat-libgcc.patch new file mode 100755 index 000000000..e6a30a3f0 --- /dev/null +++ b/misc/buildroot/toolchain/gcc/4.6.3/810-arm-softfloat-libgcc.patch @@ -0,0 +1,38 @@ +[PATCH] add the correct symbols to libgcc for uclibc arm softfloat + +Signed-off-by: Peter Korsgaard +--- + gcc/config/arm/linux-elf.h | 2 +- + gcc/config/arm/t-linux | 6 +++++- + 2 files changed, 6 insertions(+), 2 deletions(-) + +Index: gcc-4.4.0/gcc/config/arm/t-linux +=================================================================== +--- gcc-4.4.0.orig/gcc/config/arm/t-linux ++++ gcc-4.4.0/gcc/config/arm/t-linux +@@ -4,7 +4,11 @@ + + LIB1ASMSRC = arm/lib1funcs.asm + LIB1ASMFUNCS = _udivsi3 _divsi3 _umodsi3 _modsi3 _dvmd_lnx _clzsi2 _clzdi2 \ +- _arm_addsubdf3 _arm_addsubsf3 ++ _arm_addsubdf3 _arm_addsubsf3 \ ++ _arm_negdf2 _arm_muldivdf3 _arm_cmpdf2 _arm_unorddf2 \ ++ _arm_fixdfsi _arm_fixunsdfsi _arm_truncdfsf2 \ ++ _arm_negsf2 _arm_muldivsf3 _arm_cmpsf2 _arm_unordsf2 \ ++ _arm_fixsfsi _arm_fixunssfsi + + # MULTILIB_OPTIONS = mhard-float/msoft-float + # MULTILIB_DIRNAMES = hard-float soft-float +Index: gcc-4.4.0/gcc/config/arm/linux-elf.h +=================================================================== +--- gcc-4.4.0.orig/gcc/config/arm/linux-elf.h ++++ gcc-4.4.0/gcc/config/arm/linux-elf.h +@@ -60,7 +60,7 @@ + %{shared:-lc} \ + %{!shared:%{profile:-lc_p}%{!profile:-lc}}" + +-#define LIBGCC_SPEC "%{msoft-float:-lfloat} %{mfloat-abi=soft*:-lfloat} -lgcc" ++#define LIBGCC_SPEC "-lgcc" + + #define GLIBC_DYNAMIC_LINKER "/lib/ld-linux.so.2" + diff --git a/misc/buildroot/toolchain/gcc/4.6.3/820-arm-unbreak-armv4t.patch b/misc/buildroot/toolchain/gcc/4.6.3/820-arm-unbreak-armv4t.patch new file mode 100755 index 000000000..8651afcd8 --- /dev/null +++ b/misc/buildroot/toolchain/gcc/4.6.3/820-arm-unbreak-armv4t.patch @@ -0,0 +1,14 @@ +http://sourceware.org/ml/crossgcc/2008-05/msg00009.html + +diff -Nura gcc-4.5.1.orig/gcc/config/arm/linux-eabi.h gcc-4.5.1/gcc/config/arm/linux-eabi.h +--- gcc-4.5.1.orig/gcc/config/arm/linux-eabi.h 2009-10-30 17:03:09.000000000 -0300 ++++ gcc-4.5.1/gcc/config/arm/linux-eabi.h 2010-11-02 15:38:25.792208500 -0300 +@@ -44,7 +44,7 @@ + The ARM10TDMI core is the default for armv5t, so set + SUBTARGET_CPU_DEFAULT to achieve this. */ + #undef SUBTARGET_CPU_DEFAULT +-#define SUBTARGET_CPU_DEFAULT TARGET_CPU_arm10tdmi ++#define SUBTARGET_CPU_DEFAULT TARGET_CPU_arm9tdmi + + /* TARGET_BIG_ENDIAN_DEFAULT is set in + config.gcc for big endian configurations. */ diff --git a/misc/buildroot/toolchain/gcc/4.6.3/900-nuttx-nolibstdc.patch b/misc/buildroot/toolchain/gcc/4.6.3/900-nuttx-nolibstdc.patch new file mode 100755 index 000000000..5628646a6 --- /dev/null +++ b/misc/buildroot/toolchain/gcc/4.6.3/900-nuttx-nolibstdc.patch @@ -0,0 +1,13 @@ +--- gcc-4.5.2/configure.orig 2011-04-28 17:25:37.091035400 -0600 ++++ gcc-4.5.2/configure 2011-04-28 17:26:26.868332200 -0600 +@@ -3741,6 +3741,10 @@ + ;; + esac + ++# If we are building against NuttX, then don't attempt to build libstdc++ ++# (should be conditioned on --with-nuttx) ++noconfigdirs="$noconfigdirs target-libiberty target-libstdc++-v3" ++ + # If we aren't building newlib, then don't build libgloss, since libgloss + # depends upon some newlib header files. + case "${noconfigdirs}" in diff --git a/misc/buildroot/toolchain/gcc/4.6.3/powerpc-link-with-math-lib.patch.conditional b/misc/buildroot/toolchain/gcc/4.6.3/powerpc-link-with-math-lib.patch.conditional new file mode 100755 index 000000000..7e75e87f2 --- /dev/null +++ b/misc/buildroot/toolchain/gcc/4.6.3/powerpc-link-with-math-lib.patch.conditional @@ -0,0 +1,125 @@ +http://gcc.gnu.org/ml/gcc-patches/2008-10/msg00269.html + +On glibc the libc.so carries a copy of the math function copysignl() but +on uClibc math functions like copysignl() live in libm. Since libgcc_s +contains unresolved symbols, any attempt to link against libgcc_s +without explicitely specifying -lm fails, resulting in a broken +bootstrap of the compiler. + +Forward port to gcc 4.5.1 by Gustavo Zacarias + +diff -Nura gcc-4.5.1.orig/gcc/config/t-slibgcc-elf-ver gcc-4.5.1/gcc/config/t-slibgcc-elf-ver +--- gcc-4.5.1.orig/gcc/config/t-slibgcc-elf-ver 2010-11-03 14:35:08.644904042 -0300 ++++ gcc-4.5.1/gcc/config/t-slibgcc-elf-ver 2010-11-03 14:35:56.332904024 -0300 +@@ -27,7 +27,7 @@ + SHLIB_OBJS = @shlib_objs@ + SHLIB_DIR = @multilib_dir@ + SHLIB_SLIBDIR_QUAL = @shlib_slibdir_qual@ +-SHLIB_LC = -lc ++SHLIB_LC = @libgcc_libm@ -lc + SHLIB_MAKE_SOLINK = $(LN_S) $(SHLIB_SONAME) $(SHLIB_DIR)/$(SHLIB_SOLINK) + SHLIB_INSTALL_SOLINK = $(LN_S) $(SHLIB_SONAME) \ + $$(DESTDIR)$$(slibdir)$(SHLIB_SLIBDIR_QUAL)/$(SHLIB_SOLINK) +diff -Nura gcc-4.5.1.orig/libgcc/Makefile.in gcc-4.5.1/libgcc/Makefile.in +--- gcc-4.5.1.orig/libgcc/Makefile.in 2010-11-03 14:32:44.272904042 -0300 ++++ gcc-4.5.1/libgcc/Makefile.in 2010-11-03 14:37:03.893904042 -0300 +@@ -39,6 +39,7 @@ + decimal_float = @decimal_float@ + enable_decimal_float = @enable_decimal_float@ + fixed_point = @fixed_point@ ++LIBGCC_LIBM = @LIBGCC_LIBM@ + + host_noncanonical = @host_noncanonical@ + +@@ -798,9 +799,10 @@ + @multilib_dir@,$(MULTIDIR),$(subst \ + @shlib_objs@,$(objects),$(subst \ + @shlib_base_name@,libgcc_s,$(subst \ ++ @libgcc_libm@,$(LIBGCC_LIBM),$(subst \ + @shlib_map_file@,$(mapfile),$(subst \ + @shlib_slibdir_qual@,$(MULTIOSSUBDIR),$(subst \ +- @shlib_slibdir@,$(shlib_slibdir),$(SHLIB_LINK)))))))) ++ @shlib_slibdir@,$(shlib_slibdir),$(SHLIB_LINK))))))))) + + libunwind$(SHLIB_EXT): $(libunwind-s-objects) $(extra-parts) + # @multilib_flags@ is still needed because this may use +diff -Nura gcc-4.5.1.orig/libgcc/configure gcc-4.5.1/libgcc/configure +--- gcc-4.5.1.orig/libgcc/configure 2010-11-03 14:32:44.283904042 -0300 ++++ gcc-4.5.1/libgcc/configure 2010-11-03 14:39:48.685904042 -0300 +@@ -557,6 +557,7 @@ + extra_parts + tmake_file + set_use_emutls ++LIBGCC_LIBM + set_have_cc_tls + vis_hide + fixed_point +@@ -3847,6 +3848,37 @@ + set_use_emutls="-DUSE_EMUTLS" + fi + ++# On powerpc libgcc_s references copysignl which is a libm function but ++# glibc apparently also provides it via libc as opposed to uClibc where ++# it lives in libm. ++echo "$as_me:$LINENO: checking for library containing copysignl" >&5 ++echo $ECHO_N "checking for library containing copysignl... $ECHO_C" >&6 ++if test "${libgcc_cv_copysignl_lib+set}" = set; then ++ echo $ECHO_N "(cached) $ECHO_C" >&6 ++else ++ ++ echo '#include ' > conftest.c ++ echo 'int the_libc = __UCLIBC__ + __powerpc__;' >> conftest.c ++ libgcc_cv_copysignl_lib="-lc" ++ if { ac_try='${CC-cc} -S conftest.c -o conftest.s 1>&5' ++ { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5 ++ (eval $ac_try) 2>&5 ++ ac_status=$? ++ echo "$as_me:$LINENO: \$? = $ac_status" >&5 ++ (exit $ac_status); }; } ++ then ++ libgcc_cv_copysignl_lib="-lm" ++ fi ++ rm -f conftest.* ++ ++fi ++echo "$as_me:$LINENO: result: $libgcc_cv_copysignl_lib" >&5 ++echo "${ECHO_T}$libgcc_cv_copysignl_lib" >&6 ++ ++case /${libgcc_cv_copysignl_lib}/ in ++ /-lm/) LIBGCC_LIBM="$LIBGCC_LIBM -lm" ;; ++ *) LIBGCC_LIBM= ;; ++esac + + # Conditionalize the makefile for this target machine. + tmake_file_= +diff -Nura gcc-4.5.1.orig/libgcc/configure.ac gcc-4.5.1/libgcc/configure.ac +--- gcc-4.5.1.orig/libgcc/configure.ac 2010-11-03 14:32:44.735904042 -0300 ++++ gcc-4.5.1/libgcc/configure.ac 2010-11-03 14:42:11.278904045 -0300 +@@ -238,6 +238,27 @@ + fi + AC_SUBST(set_have_cc_tls) + ++# On powerpc libgcc_s references copysignl which is a libm function but ++# glibc apparently also provides it via libc as opposed to uClibc where ++# it lives in libm. ++AC_CACHE_CHECK ++ libgcc_cv_copysignl_lib, ++ echo '#include ' > conftest.c ++ echo 'int the_libc = __UCLIBC__ + __powerpc__;' >> conftest.c ++ libgcc_cv_copysignl_lib="-lc" ++ if AC_TRY_COMMAND(${CC-cc} -S conftest.c -o conftest.s 1>&AS_MESSAGE_LOG_FD) ++ then ++ libgcc_cv_copysignl_lib="-lm" ++ fi ++ rm -f conftest.* ++ ]) ++ ++case /${libgcc_cv_copysignl_lib}/ in ++ /-lm/) LIBGCC_LIBM="$LIBGCC_LIBM -lm" ;; ++ *) LIBGCC_LIBM= ;; ++esac ++AC_SUBST(LIBGCC_LIBM) ++ + # See if we have emulated thread-local storage. + GCC_CHECK_EMUTLS + set_use_emutls= diff --git a/misc/buildroot/toolchain/gcc/Config.in b/misc/buildroot/toolchain/gcc/Config.in index d2b4b69fe..822cfd4b9 100644 --- a/misc/buildroot/toolchain/gcc/Config.in +++ b/misc/buildroot/toolchain/gcc/Config.in @@ -41,6 +41,11 @@ choice select BR2_GCC_SUPPORTS_SYSROOT bool "gcc 4.5.2" + config BR2_GCC_VERSION_4_6_3 + depends on !BR2_avr32 && !BR2_nios2 && !BR2_m9s12x + select BR2_GCC_SUPPORTS_SYSROOT + bool "gcc 4.6.3" + endchoice config BR2_GCC_SUPPORTS_SYSROOT @@ -54,6 +59,7 @@ config BR2_GCC_VERSION default "4.2.4" if BR2_GCC_VERSION_4_2_4 default "4.3.3" if BR2_GCC_VERSION_4_3_3 default "4.5.2" if BR2_GCC_VERSION_4_5_2 + default "4.6.3" if BR2_GCC_VERSION_4_6_3 config BR2_GCC_USE_SJLJ_EXCEPTIONS bool "Enable setjmp/longjmp exceptions?" diff --git a/misc/buildroot/toolchain/gdb/Config.in b/misc/buildroot/toolchain/gdb/Config.in index fbea5b143..ebe8578a9 100644 --- a/misc/buildroot/toolchain/gdb/Config.in +++ b/misc/buildroot/toolchain/gdb/Config.in @@ -40,9 +40,14 @@ choice bool "gdb 6.8" depends on !BR2_avr32 + config BR2_GDB_VERSION_7_4 + config BR2_GDB_VERSION_7_4 + depends on !BR2_bfin + endchoice config BR2_GDB_VERSION string default "6.3" if BR2_GDB_VERSION_6_3 default "6.8" if BR2_GDB_VERSION_6_8 + default "7.4.1" if BR2_GDB_VERSION_7_4 diff --git a/misc/buildroot/toolchain/gdb/gdb.mk b/misc/buildroot/toolchain/gdb/gdb.mk index aa9e126bc..0f0f7e89b 100644 --- a/misc/buildroot/toolchain/gdb/gdb.mk +++ b/misc/buildroot/toolchain/gdb/gdb.mk @@ -36,7 +36,9 @@ ifeq ($(GDB_VERSION),snapshot) tar jtf $(DL_DIR)/$(GDB_SOURCE) | head -1 | cut -d"/" -f1) ln -sf $(TOOL_BUILD_DIR)/$(shell tar jtf $(DL_DIR)/$(GDB_SOURCE) | head -1 | cut -d"/" -f1) $(GDB_DIR) endif +ifneq ($(wildcard toolchain/gdb/$(GDB_VERSION)),) toolchain/patch-kernel.sh $(GDB_DIR) toolchain/gdb/$(GDB_VERSION) \*.patch +endif $(CONFIG_UPDATE) $(GDB_DIR) touch $(GDB_DIR)/.unpacked diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html index ec6a8be24..f22ab418c 100644 --- a/nuttx/Documentation/NuttX.html +++ b/nuttx/Documentation/NuttX.html @@ -1309,7 +1309,7 @@ svn checkout -r5206 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code TI TMS320C5471 (also called C5471 or TMS320DA180 or DA180). NuttX operates on the ARM7 of this dual core processor. This port uses the Spectrum Digital - evaluation board with a GNU arm-elf toolchain* under Linux or Cygwin. + evaluation board with a GNU arm-nuttx-elf toolchain* under Linux or Cygwin.

      @@ -1352,7 +1352,7 @@ svn checkout -r5206 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code NXP LPC214x. Support is provided for the NXP LPC214x family of processors. In particular, support is provided for the mcu123.com lpc214x evaluation board (LPC2148). - This port also used the GNU arm-elf toolchain* under Linux or Cygwin. + This port also used the GNU arm-nuttx-elf toolchain* under Linux or Cygwin.

        @@ -1386,7 +1386,7 @@ svn checkout -r5206 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code Support is provided for the NXP LPC2378 MCU. In particular, support is provided for the Olimex-LPC2378 development board. This port was contributed by Rommel Marcelo is was first released in NuttX-5.3. - This port also used the GNU arm-elf toolchain* under Linux or Cygwin. + This port also used the GNU arm-nuttx-elf toolchain* under Linux or Cygwin.

          @@ -1413,7 +1413,7 @@ svn checkout -r5206 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code STMicro STR71x. Support is provided for the STMicro STR71x family of processors. In particular, support is provided for the Olimex STR-P711 evaluation board. - This port also used the GNU arm-elf toolchain* under Linux or Cygwin. + This port also used the GNU arm-nuttx-elf toolchain* under Linux or Cygwin.

            @@ -1450,7 +1450,7 @@ svn checkout -r5206 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code

            Freescale MC9328MX1 or i.MX1. - This port uses the Freescale MX1ADS development board with a GNU arm-elf toolchain* + This port uses the Freescale MX1ADS development board with a GNU arm-nuttx-elf toolchain* under either Linux or Cygwin.

              @@ -1476,7 +1476,7 @@ svn checkout -r5206 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code NuttX operates on the ARM9 of this dual core processor. This port uses the Neuros OSD - with a GNU arm-elf toolchain* under Linux or Cygwin. + with a GNU arm-nuttx-elf toolchain* under Linux or Cygwin. The port was performed using the OSD v1.0, development board.

                @@ -1498,7 +1498,7 @@ svn checkout -r5206 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code NXP LPC3131. The port for the NXP LPC3131 on the Embedded Artists EA3131 - development board was first released in NuttX-5.1 with a GNU arm-elf or arm-eabi toolchain* under Linux or Cygwin + development board was first released in NuttX-5.1 with a GNU arm-nuttx-elf or arm-eabi toolchain* under Linux or Cygwin (but was not functional until NuttX-5.2).

                  @@ -1571,7 +1571,7 @@ svn checkout -r5206 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code

                  Luminary/TI Stellaris LM3S6918. This port uses the Micromint Eagle-100 development - board with a GNU arm-elf toolchain* under either Linux or Cygwin. + board with a GNU arm-nuttx-elf toolchain* under either Linux or Cygwin.

                    @@ -1601,7 +1601,7 @@ svn checkout -r5206 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code

                    Luminary/TI Stellaris LM3S6965. - This port uses the Stellaris LM3S6965 Ethernet Evalution Kit with a GNU arm-elf toolchain* + This port uses the Stellaris LM3S6965 Ethernet Evalution Kit with a GNU arm-nuttx-elf toolchain* under either Linux or Cygwin.

                      @@ -1635,7 +1635,7 @@ svn checkout -r5206 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code

                      Luminary/TI Stellaris LM3S8962. - This port uses the Stellaris EKC-LM3S8962 Ethernet+CAN Evalution Kit with a GNU arm-elf toolchain* + This port uses the Stellaris EKC-LM3S8962 Ethernet+CAN Evalution Kit with a GNU arm-nuttx-elf toolchain* under either Linux or Cygwin. Contributed by Larry Arnold.

                      @@ -1733,7 +1733,7 @@ svn checkout -r5206 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code

                      - These ports uses a GNU arm-elf toolchain* under either Linux or Cygwin (with native Windows GNU + These ports uses a GNU arm-nuttx-elf toolchain* under either Linux or Cygwin (with native Windows GNU tools or Cygwin-based GNU tools).

                        @@ -1842,7 +1842,7 @@ svn checkout -r5206 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code Atmel AT91SAM3U. This port uses the Atmel SAM3U-EK development board that features the AT91SAM3U4E MCU. - This port uses a GNU arm-elf or arm-eabi toolchain* under either Linux or Cygwin (with native Windows GNU + This port uses a GNU arm-nuttx-elf or arm-eabi toolchain* under either Linux or Cygwin (with native Windows GNU tools or Cygwin-based GNU tools).

                          @@ -1905,7 +1905,7 @@ svn checkout -r5206 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code

                          The Nucleus 2G board, the mbed board, and the LPCXpresso all feature the NXP LPC1768 MCU; the Olimex LPC1766-STK board features an LPC1766. - All use a GNU arm-elf or arm-eabi toolchain* under either Linux or Cygwin (with native Windows GNU tools or Cygwin-based GNU tools). + All use a GNU arm-nuttx-elf or arm-eabi toolchain* under either Linux or Cygwin (with native Windows GNU tools or Cygwin-based GNU tools).

                            @@ -2386,7 +2386,7 @@ svn checkout -r5206 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code

                          - Both use a GNU arm-elf toolchain* under Linux or Cygwin. + Both use a GNU arm-nuttx-elf toolchain* under Linux or Cygwin. The NuttX buildroot provides a properly patched GCC 3.4.4 toolchain that is highly optimized for the m9s12x family.

                            @@ -2696,10 +2696,10 @@ svn checkout -r5206 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code STATUS: Initial source files released in nuttx-0.4.2. At this point, the port has not been integrated; the target cannot be built - because the GNU m16c-elf-ld link fails with the following message: + because the GNU m16c-nuttx-elf-ld link fails with the following message:

                              - m32c-elf-ld: BFD (GNU Binutils) 2.19 assertion fail /home/Owner/projects/nuttx/buildroot/toolchain_build_m32c/binutils-2.19/bfd/elf32-m32c.c:482 + m32c-nuttx-elf-ld: BFD (GNU Binutils) 2.19 assertion fail /home/Owner/projects/nuttx/buildroot/toolchain_build_m32c/binutils-2.19/bfd/elf32-m32c.c:482

                            Where the reference line is:

                              @@ -3583,7 +3583,7 @@ buildroot-1.10 2011-05-06 <gnutt@nuttx.org>
                                     i486 ELF binaries.  But that will not work under Cygwin!  The Cygwin
                                     toolchain (and probably MinGW), build DOS MZ format executables (i.e.,
                                     .exe files).  That is probably not usable for most NuttX targets.
                              -      Instead, you should use this i486-elf-gcc to generate true ELF binaries
                              +      Instead, you should use this i486-nuttx-elf-gcc to generate true ELF binaries
                                     under Cygwin.
                                   * Makefile - Alter copy arguments to avoid permissions problems when
                                     copying NuttX header files.
                              diff --git a/nuttx/Documentation/NuttXLinks.html b/nuttx/Documentation/NuttXLinks.html
                              index 7196ea3ea..b69a354fa 100644
                              --- a/nuttx/Documentation/NuttXLinks.html
                              +++ b/nuttx/Documentation/NuttXLinks.html
                              @@ -22,6 +22,7 @@
                                     
                            • SourceForge
                            • FreshMeat
                            • Forum
                            • +
                            • Ohloh
                            • OSChina
                            • Downloads
                            • Wiki
                            • diff --git a/nuttx/Documentation/NuttXNxFlat.html b/nuttx/Documentation/NuttXNxFlat.html index 6f78fffcd..73be5d7b3 100644 --- a/nuttx/Documentation/NuttXNxFlat.html +++ b/nuttx/Documentation/NuttXNxFlat.html @@ -443,7 +443,7 @@ cat ../syscall/syscall.csv ../lib/lib.csv | sort >tmp.csv

                              - abc-elf-ld -r -d -warn-common -o $@ $^ + abc-nuttx-elf-ld -r -d -warn-common -o $@ $^ Target 2 @@ -464,7 +464,7 @@ cat ../syscall/syscall.csv ../lib/lib.csv | sort >tmp.csv

                              - abc-elf-ld -r -d -warn-common -T binfmt/libnxflat/gnu-nxflat.ld -no-check-sections -o $@ hello.o hello-thunk.o + abc-nuttx-elf-ld -r -d -warn-common -T binfmt/libnxflat/gnu-nxflat.ld -no-check-sections -o $@ hello.o hello-thunk.o diff --git a/nuttx/Documentation/NuttXRelated.html b/nuttx/Documentation/NuttXRelated.html index 978eb1d44..9d26a9895 100644 --- a/nuttx/Documentation/NuttXRelated.html +++ b/nuttx/Documentation/NuttXRelated.html @@ -41,7 +41,7 @@
                            • Osmocom-BB
                            • PX4 Autopilot
                            • RGMP
                            • -
                            • Top Multi-Rotor (TMR)
                            • +
                            • Top Multi-Rotor (TMR)
                            • diff --git a/nuttx/Documentation/NuttxPortingGuide.html b/nuttx/Documentation/NuttxPortingGuide.html index e13c3be62..21ae44144 100644 --- a/nuttx/Documentation/NuttxPortingGuide.html +++ b/nuttx/Documentation/NuttxPortingGuide.html @@ -768,7 +768,7 @@ This is a port to the Spectrum Digital C5471 evaluation board. The C5471 is a dual core processor from TI with an ARM7TDMI general purpose processor and a c54 DSP. It is also known as TMS320DA180 or just DA180. - NuttX runs on the ARM core and is built with with a GNU arm-elf toolchain + NuttX runs on the ARM core and is built with with a GNU arm-nuttx-elf toolchain under Linux or Cygwin. This port is complete and verified. @@ -780,14 +780,14 @@
                            • configs/ea3131: Embedded Artists EA3131 Development bard. This board is based on the - an NXP LPC3131 MCU. This OS is built with the arm-elf toolchain. + an NXP LPC3131 MCU. This OS is built with the arm-nuttx-elf toolchain. STATUS: This port is complete and mature.
                            • configs/eagle100: Micromint Eagle-100 Development board. This board is based on the an ARM Cortex-M3 MCU, the Luminary LM3S6918. This OS is built with the - arm-elf toolchain. STATUS: This port is complete and mature. + arm-nuttx-elf toolchain. STATUS: This port is complete and mature.
                            • configs/ez80f0910200kitg @@ -805,7 +805,7 @@
                            • configs/lm3s6965-ek: Stellaris LM3S6965 Evaluation Kit. This board is based on the an ARM Cortex-M3 MCU, the Luminary/TI LM3S6965. This OS is built with the - arm-elf toolchain. STATUS: This port is complete and mature. + arm-nuttx-elf toolchain. STATUS: This port is complete and mature.
                            • configs/lm3s8962-ek: @@ -827,13 +827,13 @@
                            • configs/mbed: The configurations in this directory support the mbed board (http://mbed.org) that features the NXP LPC1768 microcontroller. This OS is also built - with the arm-elf toolchain. STATUS: Contributed. + with the arm-nuttx-elf toolchain. STATUS: Contributed.
                            • configs/mcu123-lpc214x: This port is for the NXP LPC2148 as provided on the mcu123.com lpc214x development board. - This OS is also built with the arm-elf toolchain* under Linux or Cygwin. + This OS is also built with the arm-nuttx-elf toolchain* under Linux or Cygwin. The port supports serial, timer0, spi, and usb.
                            • @@ -858,7 +858,7 @@
                            • configs/ntosd-dm320: - This port uses the Neuros OSD with a GNU arm-elf toolchain* under Linux or Cygwin. + This port uses the Neuros OSD with a GNU arm-nuttx-elf toolchain* under Linux or Cygwin. See Neuros Wiki for further information. NuttX operates on the ARM9EJS of this dual core processor. @@ -878,12 +878,12 @@
                            • configs/olimex-lpc2378: - This port uses the Olimex-lpc2378 board and a GNU arm-elf toolchain under + This port uses the Olimex-lpc2378 board and a GNU arm-nuttx-elf toolchain under Linux or Cygwin. STATUS: ostest and NSH configurations available.
                            • configs/olimex-strp711: - This port uses the Olimex STR-P711 board arm-elf toolchain* under Linux or Cygwin. + This port uses the Olimex STR-P711 board arm-nuttx-elf toolchain* under Linux or Cygwin. See the Olimex web site for further information. STATUS: Configurations for the basic OS test and NSH are complete and verified. diff --git a/nuttx/Documentation/UsbTrace.html b/nuttx/Documentation/UsbTrace.html index ec48e260d..e85377756 100644 --- a/nuttx/Documentation/UsbTrace.html +++ b/nuttx/Documentation/UsbTrace.html @@ -1,332 +1,332 @@ - - -NuttX USB Trace Capability - - - -

                              - - - - -
                              -

                              NuttX USB Device Trace

                              -

                              Last Updated: March 20, 2011

                              -
                              -

                              -

                              USB Device Tracing Controls. - The NuttX USB device subsystem supports a fairly sophisticated tracing facility. - The basic trace cabability is controlled by these NuttX configuration settings: -

                              -
                                -
                              • CONFIG_USBDEV_TRACE: Enables USB tracing
                              • -
                              • CONFIG_USBDEV_TRACE_NRECORDS: Number of trace entries to remember
                              • -
                              -

                              Trace IDs. - The trace facility works like this: - When enabled, USB events that occur in either the USB device driver or in the USB class driver are logged. - These events are described in include/nuttx/usb/usbdev_trace.h. - The logged events are identified by a set of event IDs: -

                              -
                                - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
                                TRACE_INIT_IDInitialization events
                                TRACE_EP_IDEndpoint API calls
                                TRACE_DEV_IDUSB device API calls
                                TRACE_CLASS_IDUSB class driver API calls
                                TRACE_CLASSAPI_IDOther class driver system API calls
                                TRACE_CLASSSTATE_IDTrack class driver state changes
                                TRACE_INTENTRY_IDInterrupt handler entry
                                TRACE_INTDECODE_IDDecoded interrupt event
                                TRACE_INTEXIT_IDInterrupt handler exit
                                TRACE_OUTREQQUEUED_IDRequest queued for OUT endpoint
                                TRACE_INREQQUEUED_IDRequest queued for IN endpoint
                                TRACE_READ_IDRead (OUT) action
                                TRACE_WRITE_IDWrite (IN) action
                                TRACE_COMPLETE_IDRequest completed
                                TRACE_DEVERROR_IDUSB controller driver error event
                                TRACE_CLSERROR_IDUSB class driver error event
                              -

                              Logged Events. - Each logged event is 32-bits in size and includes -

                              -
                                -
                              1. 8-bits of the trace ID (values associated with the above)
                              2. -
                              3. 8-bits of additional trace ID data, and
                              4. -
                              5. 16-bits of additonal data.
                              6. -
                              -

                              8-bit Trace Data - The 8-bit trace data depends on the specific event ID. As examples, -

                              -
                                -
                              • - For the USB serial and mass storage class, the 8-bit event data is provided in include/nuttx/usb/usbdev_trace.h. -
                              • -
                              • - For the USB device driver, that 8-bit event data is provided within the USB device driver itself. - So, for example, the 8-bit event data for the LPC1768 USB device driver is found in arch/arm/src/lpc17xx/lpc17_usbdev.c. -
                              • -
                              -

                              16-bit Trace Data. - The 16-bit trace data provided additional context data relevant to the specific logged event. -

                              -

                              Trace Control Interfaces. - Logging of each of these kinds events can be enabled or disabled using the interfaces described in include/nuttx/usb/usbdev_trace.h. -

                              -

                              Enabling USB Device Tracing. - USB device tracing will be configured if CONFIG_USBDEV and either of the following are set in the NuttX configuration file: -

                              -
                                -
                              • CONFIG_USBDEV_TRACE, or
                              • -
                              • CONFIG_DEBUG and CONFIG_DEBUG_USB
                              • -
                              -

                              Log Data Sink. - The logged data itself may go to either (1) an internal circular buffer, or (2) may be provided on the console. - If CONFIG_USBDEV_TRACE is defined, then the trace data will go to the circular buffer. - The size of the circular buffer is determined by CONFIG_USBDEV_TRACE_NRECORDS. - Otherwise, the trace data goes to console. -

                              -

                              Example. - Here is an example of USB trace output using apps/examples/usbserial for an LPC1768 platform with the following NuttX configuration settings: -

                              -
                                -
                              • CONFIG_DEBUG, CONFIG_DEBUG_VERBOSE, CONFIG_USB -
                              • CONFIG_EXAMPLES_USBSERIAL_TRACEINIT, CONFIG_EXAMPLES_USBSERIAL_TRACECLASS, - CONFIG_EXAMPLES_USBSERIAL_TRACETRANSFERS, CONFIG_EXAMPLES_USBSERIAL_TRACECONTROLLER, - CONFIG_EXAMPLES_USBSERIAL_TRACEINTERRUPTS -
                              -

                              Console Output:

                              -
                                - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
                                 ABDE
                                 usbserial_main: Registering USB serial driver
                                 uart_register: Registering /dev/ttyUSB0
                                 usbserial_main: Successfully registered the serial driver
                                1Class API call 1: 0000
                                2Class error: 19:0000
                                 usbserial_main: ERROR: Failed to open /dev/ttyUSB0 for reading: 107
                                 usbserial_main: Not connected. Wait and try again.
                                3Interrupt 1 entry: 0039
                                4Interrupt decode 7: 0019
                                5Interrupt decode 32: 0019
                                6Interrupt decode 6: 0019
                                7Class disconnect(): 0000
                                8Device pullup(): 0001
                                9Interrupt 1 exit: 0000
                              -

                              - The numbered items are USB USB trace output. - You can look in the file drivers/usbdev/usbdev_trprintf.c to see examctly how each output line is formatted. - Here is how each line should be interpreted: -

                              -
                                - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
                                 USB EVENT ID8-bit
                                EVENT
                                DATA
                                MEANING16-bit
                                EVENT
                                DATA
                                1TRACE_CLASSAPI_ID11USBSER_TRACECLASSAPI_SETUP10000
                                2TRACE_CLSERROR_ID119USBSER_TRACEERR_SETUPNOTCONNECTED10000
                                3TRACE_INTENTRY_ID11LPC17_TRACEINTID_USB20039
                                4TRACE_INTDECODE_ID27LPC17_TRACEINTID_DEVSTAT20019
                                5TRACE_INTDECODE_ID232LPC17_TRACEINTID_SUSPENDCHG20019
                                6TRACE_INTDECODE_ID26LPC17_TRACEINTID_DEVRESET20019
                                7TRACE_CLASS_ID13(See TRACE_CLASSDISCONNECT1)0000
                                8TRACE_DEV_ID16(See TRACE_DEVPULLUP1)0001
                                9TRACE_INTEXIT_ID11LPC17_TRACEINTID_USB20000
                                -

                                NOTES:
                                - 1See include/nuttx/usb/usbdev_trace.h
                                - 2See arch/arm/src/lpc17xx/lpc17_usbdev.c -

                                -
                              -

                              - In the above example you can see that: -

                              -
                                -
                              • 1. - The serial class USB setup method was called for the USB serial class. - This is the corresponds to the following logic in drivers/usbdev/pl2303.c: -
                                  -static int pl2303_setup(FAR struct uart_dev_s *dev)
                                  -{
                                  -  ...
                                  -  usbtrace(PL2303_CLASSAPI_SETUP, 0);
                                  -  ...
                                  -
                                -
                              • -
                              • 2. - An error occurred while processing the setup command because no configuration has yet been selected by the host. - This corresponds to the following logic in drivers/usbdev/pl2303.c: -
                                  -static int pl2303_setup(FAR struct uart_dev_s *dev)
                                  -{
                                  -  ...
                                  -  /* Check if we have been configured */
                                  -
                                  -  if (priv->config == PL2303_CONFIGIDNONE)
                                  -    {
                                  -      usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_SETUPNOTCONNECTED), 0);
                                  -      return -ENOTCONN;
                                  -    }
                                  -  ...
                                  -
                                -
                              • 3-6. - Here is a USB interrupt that suspends and resets the device. -
                              • -
                              • 7-8. - During the interrupt processing the serial class is disconnected -
                              • -
                              • 9. - And the interrupt returns -
                              • -
                              - - + + +NuttX USB Trace Capability + + + +

                              + + + + +
                              +

                              NuttX USB Device Trace

                              +

                              Last Updated: March 20, 2011

                              +
                              +

                              +

                              USB Device Tracing Controls. + The NuttX USB device subsystem supports a fairly sophisticated tracing facility. + The basic trace cabability is controlled by these NuttX configuration settings: +

                              +
                                +
                              • CONFIG_USBDEV_TRACE: Enables USB tracing
                              • +
                              • CONFIG_USBDEV_TRACE_NRECORDS: Number of trace entries to remember
                              • +
                              +

                              Trace IDs. + The trace facility works like this: + When enabled, USB events that occur in either the USB device driver or in the USB class driver are logged. + These events are described in include/nuttx/usb/usbdev_trace.h. + The logged events are identified by a set of event IDs: +

                              +
                                + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
                                TRACE_INIT_IDInitialization events
                                TRACE_EP_IDEndpoint API calls
                                TRACE_DEV_IDUSB device API calls
                                TRACE_CLASS_IDUSB class driver API calls
                                TRACE_CLASSAPI_IDOther class driver system API calls
                                TRACE_CLASSSTATE_IDTrack class driver state changes
                                TRACE_INTENTRY_IDInterrupt handler entry
                                TRACE_INTDECODE_IDDecoded interrupt event
                                TRACE_INTEXIT_IDInterrupt handler exit
                                TRACE_OUTREQQUEUED_IDRequest queued for OUT endpoint
                                TRACE_INREQQUEUED_IDRequest queued for IN endpoint
                                TRACE_READ_IDRead (OUT) action
                                TRACE_WRITE_IDWrite (IN) action
                                TRACE_COMPLETE_IDRequest completed
                                TRACE_DEVERROR_IDUSB controller driver error event
                                TRACE_CLSERROR_IDUSB class driver error event
                              +

                              Logged Events. + Each logged event is 32-bits in size and includes +

                              +
                                +
                              1. 8-bits of the trace ID (values associated with the above)
                              2. +
                              3. 8-bits of additional trace ID data, and
                              4. +
                              5. 16-bits of additonal data.
                              6. +
                              +

                              8-bit Trace Data + The 8-bit trace data depends on the specific event ID. As examples, +

                              +
                                +
                              • + For the USB serial and mass storage class, the 8-bit event data is provided in include/nuttx/usb/usbdev_trace.h. +
                              • +
                              • + For the USB device driver, that 8-bit event data is provided within the USB device driver itself. + So, for example, the 8-bit event data for the LPC1768 USB device driver is found in arch/arm/src/lpc17xx/lpc17_usbdev.c. +
                              • +
                              +

                              16-bit Trace Data. + The 16-bit trace data provided additional context data relevant to the specific logged event. +

                              +

                              Trace Control Interfaces. + Logging of each of these kinds events can be enabled or disabled using the interfaces described in include/nuttx/usb/usbdev_trace.h. +

                              +

                              Enabling USB Device Tracing. + USB device tracing will be configured if CONFIG_USBDEV and either of the following are set in the NuttX configuration file: +

                              +
                                +
                              • CONFIG_USBDEV_TRACE, or
                              • +
                              • CONFIG_DEBUG and CONFIG_DEBUG_USB
                              • +
                              +

                              Log Data Sink. + The logged data itself may go to either (1) an internal circular buffer, or (2) may be provided on the console. + If CONFIG_USBDEV_TRACE is defined, then the trace data will go to the circular buffer. + The size of the circular buffer is determined by CONFIG_USBDEV_TRACE_NRECORDS. + Otherwise, the trace data goes to console. +

                              +

                              Example. + Here is an example of USB trace output using apps/examples/usbserial for an LPC1768 platform with the following NuttX configuration settings: +

                              +
                                +
                              • CONFIG_DEBUG, CONFIG_DEBUG_VERBOSE, CONFIG_USB +
                              • CONFIG_EXAMPLES_USBSERIAL_TRACEINIT, CONFIG_EXAMPLES_USBSERIAL_TRACECLASS, + CONFIG_EXAMPLES_USBSERIAL_TRACETRANSFERS, CONFIG_EXAMPLES_USBSERIAL_TRACECONTROLLER, + CONFIG_EXAMPLES_USBSERIAL_TRACEINTERRUPTS +
                              +

                              Console Output:

                              +
                                + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
                                 ABDE
                                 usbserial_main: Registering USB serial driver
                                 uart_register: Registering /dev/ttyUSB0
                                 usbserial_main: Successfully registered the serial driver
                                1Class API call 1: 0000
                                2Class error: 19:0000
                                 usbserial_main: ERROR: Failed to open /dev/ttyUSB0 for reading: 107
                                 usbserial_main: Not connected. Wait and try again.
                                3Interrupt 1 entry: 0039
                                4Interrupt decode 7: 0019
                                5Interrupt decode 32: 0019
                                6Interrupt decode 6: 0019
                                7Class disconnect(): 0000
                                8Device pullup(): 0001
                                9Interrupt 1 exit: 0000
                              +

                              + The numbered items are USB USB trace output. + You can look in the file drivers/usbdev/usbdev_trprintf.c to see examctly how each output line is formatted. + Here is how each line should be interpreted: +

                              +
                                + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
                                 USB EVENT ID8-bit
                                EVENT
                                DATA
                                MEANING16-bit
                                EVENT
                                DATA
                                1TRACE_CLASSAPI_ID11USBSER_TRACECLASSAPI_SETUP10000
                                2TRACE_CLSERROR_ID119USBSER_TRACEERR_SETUPNOTCONNECTED10000
                                3TRACE_INTENTRY_ID11LPC17_TRACEINTID_USB20039
                                4TRACE_INTDECODE_ID27LPC17_TRACEINTID_DEVSTAT20019
                                5TRACE_INTDECODE_ID232LPC17_TRACEINTID_SUSPENDCHG20019
                                6TRACE_INTDECODE_ID26LPC17_TRACEINTID_DEVRESET20019
                                7TRACE_CLASS_ID13(See TRACE_CLASSDISCONNECT1)0000
                                8TRACE_DEV_ID16(See TRACE_DEVPULLUP1)0001
                                9TRACE_INTEXIT_ID11LPC17_TRACEINTID_USB20000
                                +

                                NOTES:
                                + 1See include/nuttx/usb/usbdev_trace.h
                                + 2See arch/arm/src/lpc17xx/lpc17_usbdev.c +

                                +
                              +

                              + In the above example you can see that: +

                              +
                                +
                              • 1. + The serial class USB setup method was called for the USB serial class. + This is the corresponds to the following logic in drivers/usbdev/pl2303.c: +
                                  +static int pl2303_setup(FAR struct uart_dev_s *dev)
                                  +{
                                  +  ...
                                  +  usbtrace(PL2303_CLASSAPI_SETUP, 0);
                                  +  ...
                                  +
                                +
                              • +
                              • 2. + An error occurred while processing the setup command because no configuration has yet been selected by the host. + This corresponds to the following logic in drivers/usbdev/pl2303.c: +
                                  +static int pl2303_setup(FAR struct uart_dev_s *dev)
                                  +{
                                  +  ...
                                  +  /* Check if we have been configured */
                                  +
                                  +  if (priv->config == PL2303_CONFIGIDNONE)
                                  +    {
                                  +      usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_SETUPNOTCONNECTED), 0);
                                  +      return -ENOTCONN;
                                  +    }
                                  +  ...
                                  +
                                +
                              • 3-6. + Here is a USB interrupt that suspends and resets the device. +
                              • +
                              • 7-8. + During the interrupt processing the serial class is disconnected +
                              • +
                              • 9. + And the interrupt returns +
                              • +
                              + + diff --git a/nuttx/configs/Kconfig b/nuttx/configs/Kconfig index 752a5b098..600e74ef4 100644 --- a/nuttx/configs/Kconfig +++ b/nuttx/configs/Kconfig @@ -42,7 +42,7 @@ config ARCH_BOARD_C5471EVM This is a port to the Spectrum Digital C5471 evaluation board. The TMS320C5471 is a dual core processor from TI with an ARM7TDMI general purpose processor and a c54 DSP. It is also known as TMS320DA180 or just DA180. - NuttX runs on the ARM core and is built with a GNU arm-elf toolchain*. + NuttX runs on the ARM core and is built with a GNU arm-nuttx-elf toolchain*. This port is complete and verified. config ARCH_BOARD_COMPALE88 @@ -80,7 +80,7 @@ config ARCH_BOARD_EA3131 select ARCH_HAVE_BUTTONS ---help--- Embedded Artists EA3131 Development board. This board is based on the - an NXP LPC3131 MCU. This OS is built with the arm-elf toolchain*. + an NXP LPC3131 MCU. This OS is built with the arm-nuttx-elf toolchain*. STATUS: This port is complete and mature. config ARCH_BOARD_EA3152 @@ -90,7 +90,7 @@ config ARCH_BOARD_EA3152 select ARCH_HAVE_BUTTONS ---help--- Embedded Artists EA3152 Development board. This board is based on the - an NXP LPC3152 MCU. This OS is built with the arm-elf toolchain*. + an NXP LPC3152 MCU. This OS is built with the arm-nuttx-elf toolchain*. STATUS: This port is has not be exercised well, but since it is a simple derivative of the ea3131, it should be fully functional. @@ -101,7 +101,7 @@ config ARCH_BOARD_EAGLE100 ---help--- Micromint Eagle-100 Development board. This board is based on the an ARM Cortex-M3 MCU, the Luminary LM3S6918. This OS is built with the - arm-elf toolchain*. STATUS: This port is complete and mature. + arm-nuttx-elf toolchain*. STATUS: This port is complete and mature. config ARCH_BOARD_EKK_LM3S9B96 bool "TI/Stellaris EKK-LM3S9B96" @@ -184,7 +184,7 @@ config ARCH_BOARD_LM3S6965EK ---help--- Stellaris LM3S6965 Evaluation Kit. This board is based on the an ARM Cortex-M3 MCU, the Luminary/TI LM3S6965. This OS is built with the - arm-elf toolchain*. STATUS: This port is complete and mature. + arm-nuttx-elf toolchain*. STATUS: This port is complete and mature. config ARCH_BOARD_LM3S8962EK bool "Stellaris LMS38962 Evaluation Kit" @@ -215,7 +215,7 @@ config ARCH_BOARD_M68332EVB depends on ARCH_M68332 ---help--- This is a work in progress for the venerable m68322evb board from - Motorola. This OS is also built with the arm-elf toolchain. STATUS: + Motorola. This OS is also built with the arm-nuttx-elf toolchain. STATUS: This port was never completed. config ARCH_BOARD_MBED @@ -225,7 +225,7 @@ config ARCH_BOARD_MBED ---help--- The configurations in this directory support the mbed board (http://mbed.org) that features the NXP LPC1768 microcontroller. This OS is also built - with the arm-elf toolchain*. STATUS: Contributed. + with the arm-nuttx-elf toolchain*. STATUS: Contributed. config ARCH_BOARD_MCU123 bool "mcu123.com LPC2148 Development Board" @@ -233,7 +233,7 @@ config ARCH_BOARD_MCU123 select ARCH_HAVE_LEDS ---help--- This port is for the NXP LPC2148 as provided on the mcu123.com - lpc214x development board. This OS is also built with the arm-elf + lpc214x development board. This OS is also built with the arm-nuttx-elf toolchain*. The port supports serial, timer0, spi, and usb. config ARCH_BOARD_MICROPENDOUS3 @@ -270,7 +270,7 @@ config ARCH_BOARD_NTOSD_DM320 depends on ARCH_CHIP_DM320 select ARCH_HAVE_LEDS ---help--- - This port uses the Neuros OSD v1.0 Dev Board with a GNU arm-elf + This port uses the Neuros OSD v1.0 Dev Board with a GNU arm-nuttx-elf toolchain*: see http://wiki.neurostechnology.com/index.php/OSD_1.0_Developer_Home @@ -316,7 +316,7 @@ config ARCH_BOARD_OLIMEXLPC2378 depends on ARCH_CHIP_LPC2378 select ARCH_HAVE_LEDS ---help--- - This port uses the Olimex-lpc2378 board and a GNU arm-elf toolchain* under + This port uses the Olimex-lpc2378 board and a GNU arm-nuttx-elf toolchain* under Linux or Cygwin. STATUS: ostest and NSH configurations available. This port for the NXP LPC2378 was contributed by Rommel Marcelo. @@ -326,7 +326,7 @@ config ARCH_BOARD_OLIMEX_STRP711 select ARCH_HAVE_LEDS select ARCH_HAVE_BUTTONS ---help--- - This port uses the Olimex STR-P711 board and a GNU arm-elf toolchain* under + This port uses the Olimex STR-P711 board and a GNU arm-nuttx-elf toolchain* under Linux or Cygwin. See the http://www.olimex.com/dev/str-p711.html" for further information. STATUS: Configurations for the basic OS test and NSH are complete and verified. @@ -335,7 +335,7 @@ config ARCH_BOARD_OLIMEX_STM32P107 bool "Olimex STM32 P107 board" depends on ARCH_CHIP_STM32F107VC ---help--- - This port uses the Olimex STM32 P107 board and a GNU arm-elf toolchain* under + This port uses the Olimex STM32 P107 board and a GNU arm-nuttx-elf toolchain* under Linux or Cygwin. See the http://www.olimex.com for further information. This board features the STMicro STM32F107VC MCU @@ -411,7 +411,7 @@ config ARCH_BOARD_SHENZHOU select ARCH_HAVE_BUTTONS select ARCH_HAVE_IRQBUTTONS ---help--- - This port uses the Shenzhou STM32 F107 board and a GNU arm-elf toolchain* under + This port uses the Shenzhou STM32 F107 board and a GNU arm-nuttx-elf toolchain* under Linux or Cygwin. See the http://www.armjishu.com for further information. This board features the STMicro STM32F107VC MCU diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt index 5bbec874f..e6bde645d 100644 --- a/nuttx/configs/README.txt +++ b/nuttx/configs/README.txt @@ -1524,7 +1524,7 @@ configs/c5471evm This is a port to the Spectrum Digital C5471 evaluation board. The TMS320C5471 is a dual core processor from TI with an ARM7TDMI general purpose processor and a c54 DSP. It is also known as TMS320DA180 or just DA180. - NuttX runs on the ARM core and is built with a GNU arm-elf toolchain*. + NuttX runs on the ARM core and is built with a GNU arm-nuttx-elf toolchain*. This port is complete and verified. configs/compal_e88 and compal_e99 @@ -1540,19 +1540,19 @@ configs/demo9s12ne64 configs/ea3131 Embedded Artists EA3131 Development board. This board is based on the - an NXP LPC3131 MCU. This OS is built with the arm-elf toolchain*. + an NXP LPC3131 MCU. This OS is built with the arm-nuttx-elf toolchain*. STATUS: This port is complete and mature. configs/ea3152 Embedded Artists EA3152 Development board. This board is based on the - an NXP LPC3152 MCU. This OS is built with the arm-elf toolchain*. + an NXP LPC3152 MCU. This OS is built with the arm-nuttx-elf toolchain*. STATUS: This port is has not be exercised well, but since it is a simple derivative of the ea3131, it should be fully functional. configs/eagle100 Micromint Eagle-100 Development board. This board is based on the an ARM Cortex-M3 MCU, the Luminary LM3S6918. This OS is built with the - arm-elf toolchain*. STATUS: This port is complete and mature. + arm-nuttx-elf toolchain*. STATUS: This port is complete and mature. configs/ekk-lm3s9b96 TI/Stellaris EKK-LM3S9B96 board. This board is based on the @@ -1591,7 +1591,7 @@ configs/lm3s6432-s2e configs/lm3s6965-ek Stellaris LM3S6965 Evaluation Kit. This board is based on the an ARM Cortex-M3 MCU, the Luminary/TI LM3S6965. This OS is built with the - arm-elf toolchain*. STATUS: This port is complete and mature. + arm-nuttx-elf toolchain*. STATUS: This port is complete and mature. configs/lm3s8962-ek Stellaris LMS38962 Evaluation Kit. @@ -1607,17 +1607,17 @@ configs/lpc4330-xplorer configs/m68322evb This is a work in progress for the venerable m68322evb board from - Motorola. This OS is also built with the arm-elf toolchain*. STATUS: + Motorola. This OS is also built with the arm-nuttx-elf toolchain*. STATUS: This port was never completed. configs/mbed The configurations in this directory support the mbed board (http://mbed.org) that features the NXP LPC1768 microcontroller. This OS is also built - with the arm-elf toolchain*. STATUS: Contributed. + with the arm-nuttx-elf toolchain*. STATUS: Contributed. configs/mcu123-lpc214x This port is for the NXP LPC2148 as provided on the mcu123.com - lpc214x development board. This OS is also built with the arm-elf + lpc214x development board. This OS is also built with the arm-nuttx-elf toolchain*. The port supports serial, timer0, spi, and usb. configs/micropendous3 @@ -1642,7 +1642,7 @@ configs/ne64badge not yet been fully tested. configs/ntosd-dm320 - This port uses the Neuros OSD v1.0 Dev Board with a GNU arm-elf + This port uses the Neuros OSD v1.0 Dev Board with a GNU arm-nuttx-elf toolchain*: see http://wiki.neurostechnology.com/index.php/OSD_1.0_Developer_Home @@ -1666,18 +1666,18 @@ configs/olimex-lpc1766stk Linux or Cygwin. STATUS: Complete and mature. configs/olimex-lpc2378 - This port uses the Olimex-lpc2378 board and a GNU arm-elf toolchain* under + This port uses the Olimex-lpc2378 board and a GNU arm-nuttx-elf toolchain* under Linux or Cygwin. STATUS: ostest and NSH configurations available. This port for the NXP LPC2378 was contributed by Rommel Marcelo. configs/olimex-stm32-p107 - This port uses the Olimex STM32-P107 board (STM32F107VC) and a GNU arm-elf + This port uses the Olimex STM32-P107 board (STM32F107VC) and a GNU arm-nuttx-elf toolchain* under Linux or Cygwin. See the https://www.olimex.com/dev/stm32-p107.html for further information. Contributed by Max Holtzberg. STATUS: Configurations for the basic OS test and NSH are available and verified. configs/olimex-strp711 - This port uses the Olimex STR-P711 board and a GNU arm-elf toolchain* under + This port uses the Olimex STR-P711 board and a GNU arm-nuttx-elf toolchain* under Linux or Cygwin. See the http://www.olimex.com/dev/str-p711.html" for further information. STATUS: Configurations for the basic OS test and NSH are complete and verified. diff --git a/nuttx/configs/amber/hello/Make.defs b/nuttx/configs/amber/hello/Make.defs index 4474e1621..66f3ff799 100644 --- a/nuttx/configs/amber/hello/Make.defs +++ b/nuttx/configs/amber/hello/Make.defs @@ -57,7 +57,7 @@ endif ifeq ($(CONFIG_AVR_BUILDROOT),y) # NuttX buildroot GCC toolchain under Linux or Cygwin - CROSSDEV = avr-elf- + CROSSDEV = avr-nuttx-elf- MAXOPTIMIZATION = -O2 ARCHCPUFLAGS = -mmcu=atmega128 LDFLAGS += -nostartfiles -nodefaultlibs diff --git a/nuttx/configs/c5471evm/httpd/Make.defs b/nuttx/configs/c5471evm/httpd/Make.defs index 6ff007708..ffc267530 100644 --- a/nuttx/configs/c5471evm/httpd/Make.defs +++ b/nuttx/configs/c5471evm/httpd/Make.defs @@ -36,7 +36,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk -CROSSDEV = arm-elf- +CROSSDEV = arm-nuttx-elf- CC = $(CROSSDEV)gcc CPP = $(CROSSDEV)gcc -E LD = $(CROSSDEV)ld diff --git a/nuttx/configs/c5471evm/nettest/Make.defs b/nuttx/configs/c5471evm/nettest/Make.defs index d66bb564f..e784c1119 100644 --- a/nuttx/configs/c5471evm/nettest/Make.defs +++ b/nuttx/configs/c5471evm/nettest/Make.defs @@ -36,7 +36,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk -CROSSDEV = arm-elf- +CROSSDEV = arm-nuttx-elf- CC = $(CROSSDEV)gcc CPP = $(CROSSDEV)gcc -E LD = $(CROSSDEV)ld diff --git a/nuttx/configs/c5471evm/nsh/Make.defs b/nuttx/configs/c5471evm/nsh/Make.defs index 2ffb69ffd..d9e569158 100644 --- a/nuttx/configs/c5471evm/nsh/Make.defs +++ b/nuttx/configs/c5471evm/nsh/Make.defs @@ -36,7 +36,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk -CROSSDEV = arm-elf- +CROSSDEV = arm-nuttx-elf- CC = $(CROSSDEV)gcc CPP = $(CROSSDEV)gcc -E LD = $(CROSSDEV)ld diff --git a/nuttx/configs/c5471evm/ostest/Make.defs b/nuttx/configs/c5471evm/ostest/Make.defs index 04d6e0971..9cbfc1d1d 100644 --- a/nuttx/configs/c5471evm/ostest/Make.defs +++ b/nuttx/configs/c5471evm/ostest/Make.defs @@ -36,7 +36,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk -CROSSDEV = arm-elf- +CROSSDEV = arm-nuttx-elf- CC = $(CROSSDEV)gcc CPP = $(CROSSDEV)gcc -E LD = $(CROSSDEV)ld diff --git a/nuttx/configs/compal_e88/nsh_highram/Make.defs b/nuttx/configs/compal_e88/nsh_highram/Make.defs index b3c04930d..e99d5635d 100644 --- a/nuttx/configs/compal_e88/nsh_highram/Make.defs +++ b/nuttx/configs/compal_e88/nsh_highram/Make.defs @@ -45,7 +45,7 @@ EXTRA_LIBS = $(OSMODIR)/src/target/firmware/comm/libcomm.a \ # ^^^ Stupid hack! Why do I have to put it twice??? endif -CROSSDEV = arm-elf- +CROSSDEV = arm-nuttx-elf- CC = $(CROSSDEV)gcc CPP = $(CROSSDEV)gcc -E LD = $(CROSSDEV)ld diff --git a/nuttx/configs/compal_e99/nsh_compalram/Make.defs b/nuttx/configs/compal_e99/nsh_compalram/Make.defs index cec8bdd1f..4759fc76a 100644 --- a/nuttx/configs/compal_e99/nsh_compalram/Make.defs +++ b/nuttx/configs/compal_e99/nsh_compalram/Make.defs @@ -45,7 +45,7 @@ EXTRA_LIBS = $(OSMODIR)/src/target/firmware/comm/libcomm.a \ # ^^^ Stupid hack! Why do I have to put it twice??? endif -CROSSDEV = arm-elf- +CROSSDEV = arm-nuttx-elf- CC = $(CROSSDEV)gcc CPP = $(CROSSDEV)gcc -E LD = $(CROSSDEV)ld diff --git a/nuttx/configs/compal_e99/nsh_highram/Make.defs b/nuttx/configs/compal_e99/nsh_highram/Make.defs index b3c04930d..e99d5635d 100644 --- a/nuttx/configs/compal_e99/nsh_highram/Make.defs +++ b/nuttx/configs/compal_e99/nsh_highram/Make.defs @@ -45,7 +45,7 @@ EXTRA_LIBS = $(OSMODIR)/src/target/firmware/comm/libcomm.a \ # ^^^ Stupid hack! Why do I have to put it twice??? endif -CROSSDEV = arm-elf- +CROSSDEV = arm-nuttx-elf- CC = $(CROSSDEV)gcc CPP = $(CROSSDEV)gcc -E LD = $(CROSSDEV)ld diff --git a/nuttx/configs/demo9s12ne64/ostest/Make.defs b/nuttx/configs/demo9s12ne64/ostest/Make.defs index 9ad5036c3..727ebb561 100644 --- a/nuttx/configs/demo9s12ne64/ostest/Make.defs +++ b/nuttx/configs/demo9s12ne64/ostest/Make.defs @@ -39,7 +39,7 @@ include ${TOPDIR}/tools/Config.mk # Setup for the selected toolchain # NuttX buildroot under Linux or Cygwin -CROSSDEV = m9s12x-elf- +CROSSDEV = m9s12x-nuttx-elf- MAXOPTIMIZATION = -Os WINTOOL = n diff --git a/nuttx/configs/ea3131/README.txt b/nuttx/configs/ea3131/README.txt index c237345d1..a99011ec5 100644 --- a/nuttx/configs/ea3131/README.txt +++ b/nuttx/configs/ea3131/README.txt @@ -265,7 +265,7 @@ Using OpenOCD and GDB Once the OpenOCD daemon has been started, you can connect to it via GDB using the following GDB command: - arm-elf-gdb + arm-nuttx-elf-gdb (gdb) target remote localhost:3333 And you can load the NuttX ELF file: diff --git a/nuttx/configs/ea3131/nsh/Make.defs b/nuttx/configs/ea3131/nsh/Make.defs index 9ef28c363..cd49f56af 100644 --- a/nuttx/configs/ea3131/nsh/Make.defs +++ b/nuttx/configs/ea3131/nsh/Make.defs @@ -56,7 +56,7 @@ ifeq ($(CONFIG_LPC31_DEVKITARM),y) endif ifeq ($(CONFIG_LPC31_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/ea3131/ostest/Make.defs b/nuttx/configs/ea3131/ostest/Make.defs index 3528b80b5..f07f4d452 100644 --- a/nuttx/configs/ea3131/ostest/Make.defs +++ b/nuttx/configs/ea3131/ostest/Make.defs @@ -56,7 +56,7 @@ ifeq ($(CONFIG_LPC31_DEVKITARM),y) endif ifeq ($(CONFIG_LPC31_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/ea3131/pgnsh/Make.defs b/nuttx/configs/ea3131/pgnsh/Make.defs index 7dace9854..1097a8d72 100644 --- a/nuttx/configs/ea3131/pgnsh/Make.defs +++ b/nuttx/configs/ea3131/pgnsh/Make.defs @@ -56,7 +56,7 @@ ifeq ($(CONFIG_LPC31_DEVKITARM),y) endif ifeq ($(CONFIG_LPC31_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/ea3131/usbserial/Make.defs b/nuttx/configs/ea3131/usbserial/Make.defs index eb0da53f5..3fe5f8f93 100644 --- a/nuttx/configs/ea3131/usbserial/Make.defs +++ b/nuttx/configs/ea3131/usbserial/Make.defs @@ -56,7 +56,7 @@ ifeq ($(CONFIG_LPC31_DEVKITARM),y) endif ifeq ($(CONFIG_LPC31_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/ea3131/usbstorage/Make.defs b/nuttx/configs/ea3131/usbstorage/Make.defs index fc679e24c..de351b256 100644 --- a/nuttx/configs/ea3131/usbstorage/Make.defs +++ b/nuttx/configs/ea3131/usbstorage/Make.defs @@ -56,7 +56,7 @@ ifeq ($(CONFIG_LPC31_DEVKITARM),y) endif ifeq ($(CONFIG_LPC31_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/ea3152/README.txt b/nuttx/configs/ea3152/README.txt index 90be2a220..5b6eb17a9 100644 --- a/nuttx/configs/ea3152/README.txt +++ b/nuttx/configs/ea3152/README.txt @@ -264,7 +264,7 @@ Using OpenOCD and GDB Once the OpenOCD daemon has been started, you can connect to it via GDB using the following GDB command: - arm-elf-gdb + arm-nuttx-elf-gdb (gdb) target remote localhost:3333 And you can load the NuttX ELF file: diff --git a/nuttx/configs/ea3152/ostest/Make.defs b/nuttx/configs/ea3152/ostest/Make.defs index 8872b60e4..9bb350e36 100644 --- a/nuttx/configs/ea3152/ostest/Make.defs +++ b/nuttx/configs/ea3152/ostest/Make.defs @@ -56,7 +56,7 @@ ifeq ($(CONFIG_LPC31_DEVKITARM),y) endif ifeq ($(CONFIG_LPC31_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/eagle100/README.txt b/nuttx/configs/eagle100/README.txt index e03a92d5c..47c4f89df 100644 --- a/nuttx/configs/eagle100/README.txt +++ b/nuttx/configs/eagle100/README.txt @@ -36,7 +36,7 @@ GNU Toolchain Options make # Will build for the devkitARM toolchain make CROSSDEV=arm-eabi- # Will build for the devkitARM toolchain make CROSSDEV=arm-none-eabi- # Will build for the CodeSourcery toolchain - make CROSSDEV=arm-elf- # Will build for the NuttX buildroot toolchain + make CROSSDEV=arm-nuttx-elf- # Will build for the NuttX buildroot toolchain Of course, hard coding this CROSS_COMPILE value in Make.defs file will save some repetitive typing. diff --git a/nuttx/configs/eagle100/httpd/Make.defs b/nuttx/configs/eagle100/httpd/Make.defs index 1b6dc01cf..8d3cc9c25 100644 --- a/nuttx/configs/eagle100/httpd/Make.defs +++ b/nuttx/configs/eagle100/httpd/Make.defs @@ -40,7 +40,7 @@ include ${TOPDIR}/tools/Config.mk # make -- Will build for the devkitARM toolchain # make CROSSDEV=arm-eabi- -- Will build for the devkitARM toolchain # make CROSSDEV=arm-none-eabi- -- Will build for the CodeSourcery toolchain -# make CROSSDEV=arm-elf- -- Will build for the NuttX buildroot toolchain +# make CROSSDEV=arm-nuttx-elf- -- Will build for the NuttX buildroot toolchain CROSSDEV = arm-eabi- CC = $(CROSSDEV)gcc @@ -55,7 +55,7 @@ OBJDUMP = $(CROSSDEV)objdump ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} -ifeq ($(CROSSDEV),arm-elf-) +ifeq ($(CROSSDEV),arm-nuttx-elf-) MKDEP = $(TOPDIR)/tools/mkdeps.sh ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft ARCHINCLUDES = -I. -isystem $(TOPDIR)/include @@ -106,7 +106,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/eagle100/nettest/Make.defs b/nuttx/configs/eagle100/nettest/Make.defs index ef761182f..ca5049282 100644 --- a/nuttx/configs/eagle100/nettest/Make.defs +++ b/nuttx/configs/eagle100/nettest/Make.defs @@ -40,7 +40,7 @@ include ${TOPDIR}/tools/Config.mk # make -- Will build for the devkitARM toolchain # make CROSSDEV=arm-eabi- -- Will build for the devkitARM toolchain # make CROSSDEV=arm-none-eabi- -- Will build for the CodeSourcery toolchain -# make CROSSDEV=arm-elf- -- Will build for the NuttX buildroot toolchain +# make CROSSDEV=arm-nuttx-elf- -- Will build for the NuttX buildroot toolchain CROSSDEV = arm-eabi- CC = $(CROSSDEV)gcc @@ -55,7 +55,7 @@ OBJDUMP = $(CROSSDEV)objdump ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} -ifeq ($(CROSSDEV),arm-elf-) +ifeq ($(CROSSDEV),arm-nuttx-elf-) MKDEP = $(TOPDIR)/tools/mkdeps.sh ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft ARCHINCLUDES = -I. -isystem $(TOPDIR)/include @@ -106,7 +106,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/eagle100/nsh/Make.defs b/nuttx/configs/eagle100/nsh/Make.defs index 4f024e263..499299495 100644 --- a/nuttx/configs/eagle100/nsh/Make.defs +++ b/nuttx/configs/eagle100/nsh/Make.defs @@ -40,7 +40,7 @@ include ${TOPDIR}/tools/Config.mk # make -- Will build for the devkitARM toolchain # make CROSSDEV=arm-eabi- -- Will build for the devkitARM toolchain # make CROSSDEV=arm-none-eabi- -- Will build for the CodeSourcery toolchain -# make CROSSDEV=arm-elf- -- Will build for the NuttX buildroot toolchain +# make CROSSDEV=arm-nuttx-elf- -- Will build for the NuttX buildroot toolchain CROSSDEV = arm-eabi- CC = $(CROSSDEV)gcc @@ -55,7 +55,7 @@ OBJDUMP = $(CROSSDEV)objdump ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} -ifeq ($(CROSSDEV),arm-elf-) +ifeq ($(CROSSDEV),arm-nuttx-elf-) MKDEP = $(TOPDIR)/tools/mkdeps.sh ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft ARCHINCLUDES = -I. -isystem $(TOPDIR)/include @@ -106,7 +106,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/eagle100/nxflat/Make.defs b/nuttx/configs/eagle100/nxflat/Make.defs index d3107f112..d735c3942 100644 --- a/nuttx/configs/eagle100/nxflat/Make.defs +++ b/nuttx/configs/eagle100/nxflat/Make.defs @@ -40,7 +40,7 @@ include ${TOPDIR}/tools/Config.mk # make -- Will build for the devkitARM toolchain # make CROSSDEV=arm-eabi- -- Will build for the devkitARM toolchain # make CROSSDEV=arm-none-eabi- -- Will build for the CodeSourcery toolchain -# make CROSSDEV=arm-elf- -- Will build for the NuttX buildroot toolchain +# make CROSSDEV=arm-nuttx-elf- -- Will build for the NuttX buildroot toolchain CROSSDEV = arm-eabi- CC = $(CROSSDEV)gcc @@ -58,7 +58,7 @@ LDNXFLAT = ldnxflat ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} -ifeq ($(CROSSDEV),arm-elf-) +ifeq ($(CROSSDEV),arm-nuttx-elf-) MKDEP = $(TOPDIR)/tools/mkdeps.sh ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft ARCHINCLUDES = -I. -isystem $(TOPDIR)/include @@ -109,7 +109,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/eagle100/ostest/Make.defs b/nuttx/configs/eagle100/ostest/Make.defs index 7dd98c21a..641fcbaba 100644 --- a/nuttx/configs/eagle100/ostest/Make.defs +++ b/nuttx/configs/eagle100/ostest/Make.defs @@ -40,7 +40,7 @@ include ${TOPDIR}/tools/Config.mk # make -- Will build for the devkitARM toolchain # make CROSSDEV=arm-eabi- -- Will build for the devkitARM toolchain # make CROSSDEV=arm-none-eabi- -- Will build for the CodeSourcery toolchain -# make CROSSDEV=arm-elf- -- Will build for the NuttX buildroot toolchain +# make CROSSDEV=arm-nuttx-elf- -- Will build for the NuttX buildroot toolchain CROSSDEV = arm-eabi- CC = $(CROSSDEV)gcc @@ -55,7 +55,7 @@ OBJDUMP = $(CROSSDEV)objdump ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} -ifeq ($(CROSSDEV),arm-elf-) +ifeq ($(CROSSDEV),arm-nuttx-elf-) MKDEP = $(TOPDIR)/tools/mkdeps.sh ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft ARCHINCLUDES = -I. -isystem $(TOPDIR)/include @@ -106,7 +106,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/eagle100/thttpd/Make.defs b/nuttx/configs/eagle100/thttpd/Make.defs index a864867e7..999db3a59 100644 --- a/nuttx/configs/eagle100/thttpd/Make.defs +++ b/nuttx/configs/eagle100/thttpd/Make.defs @@ -40,7 +40,7 @@ include ${TOPDIR}/tools/Config.mk # make -- Will build for the devkitARM toolchain # make CROSSDEV=arm-eabi- -- Will build for the devkitARM toolchain # make CROSSDEV=arm-none-eabi- -- Will build for the CodeSourcery toolchain -# make CROSSDEV=arm-elf- -- Will build for the NuttX buildroot toolchain +# make CROSSDEV=arm-nuttx-elf- -- Will build for the NuttX buildroot toolchain CROSSDEV = arm-eabi- CC = $(CROSSDEV)gcc @@ -58,7 +58,7 @@ LDNXFLAT = ldnxflat ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} -ifeq ($(CROSSDEV),arm-elf-) +ifeq ($(CROSSDEV),arm-nuttx-elf-) MKDEP = $(TOPDIR)/tools/mkdeps.sh ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft ARCHINCLUDES = -I. -isystem $(TOPDIR)/include @@ -109,7 +109,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/ekk-lm3s9b96/nsh/Make.defs b/nuttx/configs/ekk-lm3s9b96/nsh/Make.defs index a4223e513..1be7fc8f0 100644 --- a/nuttx/configs/ekk-lm3s9b96/nsh/Make.defs +++ b/nuttx/configs/ekk-lm3s9b96/nsh/Make.defs @@ -59,7 +59,7 @@ ifeq ($(CONFIG_LM3S_DEVKITARM),y) endif ifeq ($(CONFIG_LM3S_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -121,7 +121,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/ekk-lm3s9b96/ostest/Make.defs b/nuttx/configs/ekk-lm3s9b96/ostest/Make.defs index 2da0c421a..e0fae20f0 100644 --- a/nuttx/configs/ekk-lm3s9b96/ostest/Make.defs +++ b/nuttx/configs/ekk-lm3s9b96/ostest/Make.defs @@ -59,7 +59,7 @@ ifeq ($(CONFIG_LM3S_DEVKITARM),y) endif ifeq ($(CONFIG_LM3S_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -121,7 +121,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/fire-stm32v2/nsh/Make.defs b/nuttx/configs/fire-stm32v2/nsh/Make.defs index 567e82063..aaf0e8980 100644 --- a/nuttx/configs/fire-stm32v2/nsh/Make.defs +++ b/nuttx/configs/fire-stm32v2/nsh/Make.defs @@ -82,8 +82,8 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- - ARCROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- + ARCROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -153,7 +153,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/hymini-stm32v/buttons/Make.defs b/nuttx/configs/hymini-stm32v/buttons/Make.defs index f78c3aed3..bcc1f6845 100644 --- a/nuttx/configs/hymini-stm32v/buttons/Make.defs +++ b/nuttx/configs/hymini-stm32v/buttons/Make.defs @@ -70,7 +70,7 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -132,7 +132,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/hymini-stm32v/nsh/Make.defs b/nuttx/configs/hymini-stm32v/nsh/Make.defs index 91aa06383..fae6edc08 100644 --- a/nuttx/configs/hymini-stm32v/nsh/Make.defs +++ b/nuttx/configs/hymini-stm32v/nsh/Make.defs @@ -70,7 +70,7 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -132,7 +132,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/hymini-stm32v/nsh2/Make.defs b/nuttx/configs/hymini-stm32v/nsh2/Make.defs index f5c9d11c6..1cf89238e 100644 --- a/nuttx/configs/hymini-stm32v/nsh2/Make.defs +++ b/nuttx/configs/hymini-stm32v/nsh2/Make.defs @@ -70,7 +70,7 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -132,7 +132,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/hymini-stm32v/nx/Make.defs b/nuttx/configs/hymini-stm32v/nx/Make.defs index ac140b354..8ebded094 100644 --- a/nuttx/configs/hymini-stm32v/nx/Make.defs +++ b/nuttx/configs/hymini-stm32v/nx/Make.defs @@ -70,7 +70,7 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -132,7 +132,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/hymini-stm32v/nxlines/Make.defs b/nuttx/configs/hymini-stm32v/nxlines/Make.defs index 897af1fcd..15521d621 100644 --- a/nuttx/configs/hymini-stm32v/nxlines/Make.defs +++ b/nuttx/configs/hymini-stm32v/nxlines/Make.defs @@ -73,7 +73,7 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -134,7 +134,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/hymini-stm32v/usbserial/Make.defs b/nuttx/configs/hymini-stm32v/usbserial/Make.defs index 29be9190f..b58c4c1fe 100644 --- a/nuttx/configs/hymini-stm32v/usbserial/Make.defs +++ b/nuttx/configs/hymini-stm32v/usbserial/Make.defs @@ -70,7 +70,7 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -132,7 +132,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/hymini-stm32v/usbstorage/Make.defs b/nuttx/configs/hymini-stm32v/usbstorage/Make.defs index 3e89daa6d..f3264ab93 100644 --- a/nuttx/configs/hymini-stm32v/usbstorage/Make.defs +++ b/nuttx/configs/hymini-stm32v/usbstorage/Make.defs @@ -70,7 +70,7 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -132,7 +132,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/kwikstik-k40/ostest/Make.defs b/nuttx/configs/kwikstik-k40/ostest/Make.defs index 0f03b6c19..43a5dd01e 100644 --- a/nuttx/configs/kwikstik-k40/ostest/Make.defs +++ b/nuttx/configs/kwikstik-k40/ostest/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_KINETIS_DEVKITARM),y) endif ifeq ($(CONFIG_KINETIS_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft -mlong-calls MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/lincoln60/nsh/Make.defs b/nuttx/configs/lincoln60/nsh/Make.defs index cca519da4..9750a0e87 100644 --- a/nuttx/configs/lincoln60/nsh/Make.defs +++ b/nuttx/configs/lincoln60/nsh/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/lincoln60/ostest/Make.defs b/nuttx/configs/lincoln60/ostest/Make.defs index 29ef7c327..c90939429 100644 --- a/nuttx/configs/lincoln60/ostest/Make.defs +++ b/nuttx/configs/lincoln60/ostest/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/lm3s6432-s2e/nsh/Make.defs b/nuttx/configs/lm3s6432-s2e/nsh/Make.defs index 3bac1a4db..ef39674b2 100644 --- a/nuttx/configs/lm3s6432-s2e/nsh/Make.defs +++ b/nuttx/configs/lm3s6432-s2e/nsh/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LM3S_DEVKITARM),y) endif ifeq ($(CONFIG_LM3S_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/lm3s6432-s2e/ostest/Make.defs b/nuttx/configs/lm3s6432-s2e/ostest/Make.defs index 7d528cdf0..603689183 100644 --- a/nuttx/configs/lm3s6432-s2e/ostest/Make.defs +++ b/nuttx/configs/lm3s6432-s2e/ostest/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LM3S_DEVKITARM),y) endif ifeq ($(CONFIG_LM3S_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/lm3s6965-ek/nsh/Make.defs b/nuttx/configs/lm3s6965-ek/nsh/Make.defs index 52a3c7bd1..17df0ebf7 100644 --- a/nuttx/configs/lm3s6965-ek/nsh/Make.defs +++ b/nuttx/configs/lm3s6965-ek/nsh/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LM3S_DEVKITARM),y) endif ifeq ($(CONFIG_LM3S_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/lm3s6965-ek/nx/Make.defs b/nuttx/configs/lm3s6965-ek/nx/Make.defs index 21b60450f..5ab0cfd26 100644 --- a/nuttx/configs/lm3s6965-ek/nx/Make.defs +++ b/nuttx/configs/lm3s6965-ek/nx/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LM3S_DEVKITARM),y) endif ifeq ($(CONFIG_LM3S_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/lm3s6965-ek/ostest/Make.defs b/nuttx/configs/lm3s6965-ek/ostest/Make.defs index a834a57ef..5e49273a0 100644 --- a/nuttx/configs/lm3s6965-ek/ostest/Make.defs +++ b/nuttx/configs/lm3s6965-ek/ostest/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LM3S_DEVKITARM),y) endif ifeq ($(CONFIG_LM3S_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/lm3s8962-ek/nsh/Make.defs b/nuttx/configs/lm3s8962-ek/nsh/Make.defs index c37875c64..cc7bce1e5 100644 --- a/nuttx/configs/lm3s8962-ek/nsh/Make.defs +++ b/nuttx/configs/lm3s8962-ek/nsh/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LM3S_DEVKITARM),y) endif ifeq ($(CONFIG_LM3S_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/lm3s8962-ek/nx/Make.defs b/nuttx/configs/lm3s8962-ek/nx/Make.defs index be150074c..b97aaa31e 100644 --- a/nuttx/configs/lm3s8962-ek/nx/Make.defs +++ b/nuttx/configs/lm3s8962-ek/nx/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LM3S_DEVKITARM),y) endif ifeq ($(CONFIG_LM3S_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/lm3s8962-ek/ostest/Make.defs b/nuttx/configs/lm3s8962-ek/ostest/Make.defs index 43bcfcddd..4b4863d7c 100644 --- a/nuttx/configs/lm3s8962-ek/ostest/Make.defs +++ b/nuttx/configs/lm3s8962-ek/ostest/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LM3S_DEVKITARM),y) endif ifeq ($(CONFIG_LM3S_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/lpc4330-xplorer/nsh/Make.defs b/nuttx/configs/lpc4330-xplorer/nsh/Make.defs index 341671a97..960fb2a41 100644 --- a/nuttx/configs/lpc4330-xplorer/nsh/Make.defs +++ b/nuttx/configs/lpc4330-xplorer/nsh/Make.defs @@ -93,8 +93,8 @@ ifeq ($(CONFIG_LPC43_DEVKITARM),y) endif ifeq ($(CONFIG_LPC43_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- - ARCROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- + ARCROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m4 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -176,7 +176,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/lpc4330-xplorer/ostest/Make.defs b/nuttx/configs/lpc4330-xplorer/ostest/Make.defs index 341671a97..960fb2a41 100644 --- a/nuttx/configs/lpc4330-xplorer/ostest/Make.defs +++ b/nuttx/configs/lpc4330-xplorer/ostest/Make.defs @@ -93,8 +93,8 @@ ifeq ($(CONFIG_LPC43_DEVKITARM),y) endif ifeq ($(CONFIG_LPC43_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- - ARCROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- + ARCROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m4 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -176,7 +176,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/lpcxpresso-lpc1768/dhcpd/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/dhcpd/Make.defs index 8ece92ca9..804e20ecd 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/dhcpd/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/dhcpd/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -132,7 +132,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/lpcxpresso-lpc1768/nsh/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/nsh/Make.defs index 21d84b494..8c6ad9ab8 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/nsh/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/nsh/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -132,7 +132,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/lpcxpresso-lpc1768/nx/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/nx/Make.defs index 9a7d19069..a535fd03d 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/nx/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/nx/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -132,7 +132,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/lpcxpresso-lpc1768/ostest/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/ostest/Make.defs index 1dd92adb7..1b38f2d6b 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/ostest/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/ostest/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -132,7 +132,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/lpcxpresso-lpc1768/thttpd/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/thttpd/Make.defs index fc40cce07..810d6d7da 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/thttpd/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/thttpd/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -137,7 +137,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/lpcxpresso-lpc1768/usbstorage/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/usbstorage/Make.defs index d63e11efe..5342dde5b 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/usbstorage/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/usbstorage/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -132,7 +132,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/m68332evb/Make.defs b/nuttx/configs/m68332evb/Make.defs index fdae944f0..fb85cf827 100644 --- a/nuttx/configs/m68332evb/Make.defs +++ b/nuttx/configs/m68332evb/Make.defs @@ -50,7 +50,7 @@ ARCHDEFINES = ARCHINCLUDES = -I. -isystem $(TOPDIR)/include ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/ld.script -CROSSDEV = m68k-elf- +CROSSDEV = m68k-nuttx-elf- CC = $(CROSSDEV)gcc CPP = $(CROSSDEV)gcc -E LD = $(CROSSDEV)ld diff --git a/nuttx/configs/m68332evb/doc/m68k-defconfig b/nuttx/configs/m68332evb/doc/m68k-defconfig index cbe3c11cd..60f2e4cbd 100644 --- a/nuttx/configs/m68332evb/doc/m68k-defconfig +++ b/nuttx/configs/m68332evb/doc/m68k-defconfig @@ -34,7 +34,7 @@ BR2_STAGING_DIR="$(BUILD_DIR)/staging_dir" BR2_NUTTX_DIR="$(TOPDIR)/../nuttx" BR2_TOPDIR_PREFIX="" BR2_TOPDIR_SUFFIX="" -BR2_GNU_BUILD_SUFFIX="m68k-elf" +BR2_GNU_BUILD_SUFFIX="m68k-nuttx-elf" BR2_GNU_TARGET_SUFFIX="elf" # BR2_PREFER_IMA is not set # BR2_DEPRECATED is not set diff --git a/nuttx/configs/mbed/hidkbd/Make.defs b/nuttx/configs/mbed/hidkbd/Make.defs index f033c685e..262571e45 100644 --- a/nuttx/configs/mbed/hidkbd/Make.defs +++ b/nuttx/configs/mbed/hidkbd/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/mbed/nsh/Make.defs b/nuttx/configs/mbed/nsh/Make.defs index 468952aa2..40c4c94f3 100644 --- a/nuttx/configs/mbed/nsh/Make.defs +++ b/nuttx/configs/mbed/nsh/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/mcu123-lpc214x/README.txt b/nuttx/configs/mcu123-lpc214x/README.txt index 8236798cc..b819abf36 100644 --- a/nuttx/configs/mcu123-lpc214x/README.txt +++ b/nuttx/configs/mcu123-lpc214x/README.txt @@ -42,7 +42,7 @@ GNU Toolchain Options make # Will build for the NuttX buildroot toolchain make CROSSDEV=arm-eabi- # Will build for the devkitARM toolchain make CROSSDEV=arm-none-eabi- # Will build for the CodeSourcery toolchain - make CROSSDEV=arm-elf- # Will build for the NuttX buildroot toolchain + make CROSSDEV=arm-nuttx-elf- # Will build for the NuttX buildroot toolchain Of course, hard coding this CROSS_COMPILE value in Make.defs file will save some repetitive typing. diff --git a/nuttx/configs/mcu123-lpc214x/composite/Make.defs b/nuttx/configs/mcu123-lpc214x/composite/Make.defs index 0173a21c6..f2f0ee8e8 100644 --- a/nuttx/configs/mcu123-lpc214x/composite/Make.defs +++ b/nuttx/configs/mcu123-lpc214x/composite/Make.defs @@ -40,7 +40,7 @@ include ${TOPDIR}/tools/Config.mk # make -- Will build for the CodeSourcery toolchain # make CROSSDEV=arm-eabi- -- Will build for the devkitARM toolchain # make CROSSDEV=arm-none-eabi- -- Will build for the CodeSourcery toolchain -# make CROSSDEV=arm-elf- -- Will build for the NuttX buildroot toolchain +# make CROSSDEV=arm-nuttx-elf- -- Will build for the NuttX buildroot toolchain CROSSDEV = arm-none-eabi- CC = $(CROSSDEV)gcc @@ -63,7 +63,7 @@ OBJCOPYARGS = -R .note -R .note.gnu.build-id -R .comment endif endif -ifeq ($(CROSSDEV),arm-elf-) +ifeq ($(CROSSDEV),arm-nuttx-elf-) MKDEP = $(TOPDIR)/tools/mkdeps.sh ARCHINCLUDES = -I. -isystem $(TOPDIR)/include ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx @@ -118,7 +118,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/mcu123-lpc214x/nsh/Make.defs b/nuttx/configs/mcu123-lpc214x/nsh/Make.defs index daa7a3466..de09916e5 100644 --- a/nuttx/configs/mcu123-lpc214x/nsh/Make.defs +++ b/nuttx/configs/mcu123-lpc214x/nsh/Make.defs @@ -40,9 +40,9 @@ include ${TOPDIR}/tools/Config.mk # make -- Will build for the NuttX buildroot toolchain # make CROSSDEV=arm-eabi- -- Will build for the devkitARM toolchain # make CROSSDEV=arm-none-eabi- -- Will build for the CodeSourcery toolchain -# make CROSSDEV=arm-elf- -- Will build for the NuttX buildroot toolchain +# make CROSSDEV=arm-nuttx-elf- -- Will build for the NuttX buildroot toolchain -CROSSDEV = arm-elf- +CROSSDEV = arm-nuttx-elf- CC = $(CROSSDEV)gcc CXX = $(CROSSDEV)g++ CPP = $(CROSSDEV)gcc -E @@ -63,7 +63,7 @@ OBJCOPYARGS = -R .note -R .note.gnu.build-id -R .comment endif endif -ifeq ($(CROSSDEV),arm-elf-) +ifeq ($(CROSSDEV),arm-nuttx-elf-) MKDEP = $(TOPDIR)/tools/mkdeps.sh ARCHINCLUDES = -I. -isystem $(TOPDIR)/include ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx @@ -118,7 +118,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/mcu123-lpc214x/ostest/Make.defs b/nuttx/configs/mcu123-lpc214x/ostest/Make.defs index d807c7bbd..bc72ca9bd 100644 --- a/nuttx/configs/mcu123-lpc214x/ostest/Make.defs +++ b/nuttx/configs/mcu123-lpc214x/ostest/Make.defs @@ -40,9 +40,9 @@ include ${TOPDIR}/tools/Config.mk # make -- Will build for the NuttX buildroot toolchain # make CROSSDEV=arm-eabi- -- Will build for the devkitARM toolchain # make CROSSDEV=arm-none-eabi- -- Will build for the CodeSourcery toolchain -# make CROSSDEV=arm-elf- -- Will build for the NuttX buildroot toolchain +# make CROSSDEV=arm-nuttx-elf- -- Will build for the NuttX buildroot toolchain -CROSSDEV = arm-elf- +CROSSDEV = arm-nuttx-elf- CC = $(CROSSDEV)gcc CXX = $(CROSSDEV)g++ CPP = $(CROSSDEV)gcc -E @@ -63,7 +63,7 @@ OBJCOPYARGS = -R .note -R .note.gnu.build-id -R .comment endif endif -ifeq ($(CROSSDEV),arm-elf-) +ifeq ($(CROSSDEV),arm-nuttx-elf-) MKDEP = $(TOPDIR)/tools/mkdeps.sh ARCHINCLUDES = -I. -isystem $(TOPDIR)/include ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx @@ -118,7 +118,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/mcu123-lpc214x/usbserial/Make.defs b/nuttx/configs/mcu123-lpc214x/usbserial/Make.defs index 22edf3bab..106224ef1 100644 --- a/nuttx/configs/mcu123-lpc214x/usbserial/Make.defs +++ b/nuttx/configs/mcu123-lpc214x/usbserial/Make.defs @@ -40,9 +40,9 @@ include ${TOPDIR}/tools/Config.mk # make -- Will build for the NuttX buildroot toolchain # make CROSSDEV=arm-eabi- -- Will build for the devkitARM toolchain # make CROSSDEV=arm-none-eabi- -- Will build for the CodeSourcery toolchain -# make CROSSDEV=arm-elf- -- Will build for the NuttX buildroot toolchain +# make CROSSDEV=arm-nuttx-elf- -- Will build for the NuttX buildroot toolchain -CROSSDEV = arm-elf- +CROSSDEV = arm-nuttx-elf- CC = $(CROSSDEV)gcc CXX = $(CROSSDEV)g++ CPP = $(CROSSDEV)gcc -E @@ -63,7 +63,7 @@ OBJCOPYARGS = -R .note -R .note.gnu.build-id -R .comment endif endif -ifeq ($(CROSSDEV),arm-elf-) +ifeq ($(CROSSDEV),arm-nuttx-elf-) MKDEP = $(TOPDIR)/tools/mkdeps.sh ARCHINCLUDES = -I. -isystem $(TOPDIR)/include ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx @@ -118,7 +118,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/mcu123-lpc214x/usbstorage/Make.defs b/nuttx/configs/mcu123-lpc214x/usbstorage/Make.defs index 732a6733b..bf1b9cab4 100644 --- a/nuttx/configs/mcu123-lpc214x/usbstorage/Make.defs +++ b/nuttx/configs/mcu123-lpc214x/usbstorage/Make.defs @@ -40,9 +40,9 @@ include ${TOPDIR}/tools/Config.mk # make -- Will build for the NuttX buildroot toolchain # make CROSSDEV=arm-eabi- -- Will build for the devkitARM toolchain # make CROSSDEV=arm-none-eabi- -- Will build for the CodeSourcery toolchain -# make CROSSDEV=arm-elf- -- Will build for the NuttX buildroot toolchain +# make CROSSDEV=arm-nuttx-elf- -- Will build for the NuttX buildroot toolchain -CROSSDEV = arm-elf- +CROSSDEV = arm-nuttx-elf- CC = $(CROSSDEV)gcc CXX = $(CROSSDEV)g++ CPP = $(CROSSDEV)gcc -E @@ -63,7 +63,7 @@ OBJCOPYARGS = -R .note -R .note.gnu.build-id -R .comment endif endif -ifeq ($(CROSSDEV),arm-elf-) +ifeq ($(CROSSDEV),arm-nuttx-elf-) MKDEP = $(TOPDIR)/tools/mkdeps.sh ARCHINCLUDES = -I. -isystem $(TOPDIR)/include ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx @@ -118,7 +118,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/micropendous3/README.txt b/nuttx/configs/micropendous3/README.txt index e7b2041aa..c05f1ddd5 100644 --- a/nuttx/configs/micropendous3/README.txt +++ b/nuttx/configs/micropendous3/README.txt @@ -523,7 +523,7 @@ Where is one of the following: FLASH/SRAM Requirements (as of 6/16/2011): - $ avr-elf-size nuttx + $ avr-nuttx-elf-size nuttx text data bss dec hex filename 24816 978 308 26102 65f6 nuttx diff --git a/nuttx/configs/micropendous3/hello/Make.defs b/nuttx/configs/micropendous3/hello/Make.defs index 058f16690..178f35556 100644 --- a/nuttx/configs/micropendous3/hello/Make.defs +++ b/nuttx/configs/micropendous3/hello/Make.defs @@ -57,7 +57,7 @@ endif ifeq ($(CONFIG_AVR_BUILDROOT),y) # NuttX buildroot GCC toolchain under Linux or Cygwin - CROSSDEV = avr-elf- + CROSSDEV = avr-nuttx-elf- MAXOPTIMIZATION = -O2 ARCHCPUFLAGS = -mmcu=at90usb647 LDFLAGS += -nostartfiles -nodefaultlibs diff --git a/nuttx/configs/mx1ads/ostest/Make.defs b/nuttx/configs/mx1ads/ostest/Make.defs index c80af5c62..71e053b0a 100644 --- a/nuttx/configs/mx1ads/ostest/Make.defs +++ b/nuttx/configs/mx1ads/ostest/Make.defs @@ -36,7 +36,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk -CROSSDEV = arm-elf- +CROSSDEV = arm-nuttx-elf- CC = $(CROSSDEV)gcc CXX = $(CROSSDEV)g++ CPP = $(CROSSDEV)gcc -E diff --git a/nuttx/configs/ne64badge/ostest/Make.defs b/nuttx/configs/ne64badge/ostest/Make.defs index 4dc164d15..9521a0a66 100644 --- a/nuttx/configs/ne64badge/ostest/Make.defs +++ b/nuttx/configs/ne64badge/ostest/Make.defs @@ -39,7 +39,7 @@ include ${TOPDIR}/tools/Config.mk # Setup for the selected toolchain # NuttX buildroot under Linux or Cygwin -CROSSDEV = m9s12x-elf- +CROSSDEV = m9s12x-nuttx-elf- MAXOPTIMIZATION = -Os WINTOOL = n diff --git a/nuttx/configs/ntosd-dm320/nettest/Make.defs b/nuttx/configs/ntosd-dm320/nettest/Make.defs index b3d49bc73..30d369c2a 100644 --- a/nuttx/configs/ntosd-dm320/nettest/Make.defs +++ b/nuttx/configs/ntosd-dm320/nettest/Make.defs @@ -56,7 +56,7 @@ ifeq ($(CONFIG_DM320_DEVKITARM),y) endif ifeq ($(CONFIG_DM320_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/ntosd-dm320/nsh/Make.defs b/nuttx/configs/ntosd-dm320/nsh/Make.defs index 6a590a442..14038f756 100644 --- a/nuttx/configs/ntosd-dm320/nsh/Make.defs +++ b/nuttx/configs/ntosd-dm320/nsh/Make.defs @@ -56,7 +56,7 @@ ifeq ($(CONFIG_DM320_DEVKITARM),y) endif ifeq ($(CONFIG_DM320_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/ntosd-dm320/ostest/Make.defs b/nuttx/configs/ntosd-dm320/ostest/Make.defs index dda36c8fe..4618c4246 100644 --- a/nuttx/configs/ntosd-dm320/ostest/Make.defs +++ b/nuttx/configs/ntosd-dm320/ostest/Make.defs @@ -56,7 +56,7 @@ ifeq ($(CONFIG_DM320_DEVKITARM),y) endif ifeq ($(CONFIG_DM320_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/ntosd-dm320/poll/Make.defs b/nuttx/configs/ntosd-dm320/poll/Make.defs index a3abff2ef..c06139bd6 100644 --- a/nuttx/configs/ntosd-dm320/poll/Make.defs +++ b/nuttx/configs/ntosd-dm320/poll/Make.defs @@ -56,7 +56,7 @@ ifeq ($(CONFIG_DM320_DEVKITARM),y) endif ifeq ($(CONFIG_DM320_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/ntosd-dm320/thttpd/Make.defs b/nuttx/configs/ntosd-dm320/thttpd/Make.defs index 40ecf053f..075f72eaa 100644 --- a/nuttx/configs/ntosd-dm320/thttpd/Make.defs +++ b/nuttx/configs/ntosd-dm320/thttpd/Make.defs @@ -56,7 +56,7 @@ ifeq ($(CONFIG_DM320_DEVKITARM),y) endif ifeq ($(CONFIG_DM320_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/ntosd-dm320/udp/Make.defs b/nuttx/configs/ntosd-dm320/udp/Make.defs index 6122aeb11..66750f13d 100644 --- a/nuttx/configs/ntosd-dm320/udp/Make.defs +++ b/nuttx/configs/ntosd-dm320/udp/Make.defs @@ -56,7 +56,7 @@ ifeq ($(CONFIG_DM320_DEVKITARM),y) endif ifeq ($(CONFIG_DM320_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/ntosd-dm320/uip/Make.defs b/nuttx/configs/ntosd-dm320/uip/Make.defs index 758924a15..d59b96e7c 100644 --- a/nuttx/configs/ntosd-dm320/uip/Make.defs +++ b/nuttx/configs/ntosd-dm320/uip/Make.defs @@ -56,7 +56,7 @@ ifeq ($(CONFIG_DM320_DEVKITARM),y) endif ifeq ($(CONFIG_DM320_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/nucleus2g/nsh/Make.defs b/nuttx/configs/nucleus2g/nsh/Make.defs index 65ec1c8f0..3b8f857a6 100644 --- a/nuttx/configs/nucleus2g/nsh/Make.defs +++ b/nuttx/configs/nucleus2g/nsh/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/nucleus2g/ostest/Make.defs b/nuttx/configs/nucleus2g/ostest/Make.defs index 413f40178..aa0e6f864 100644 --- a/nuttx/configs/nucleus2g/ostest/Make.defs +++ b/nuttx/configs/nucleus2g/ostest/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/nucleus2g/usbserial/Make.defs b/nuttx/configs/nucleus2g/usbserial/Make.defs index 5e473323e..483fd5260 100644 --- a/nuttx/configs/nucleus2g/usbserial/Make.defs +++ b/nuttx/configs/nucleus2g/usbserial/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/nucleus2g/usbstorage/Make.defs b/nuttx/configs/nucleus2g/usbstorage/Make.defs index 35487f85b..7a9c1fa6b 100644 --- a/nuttx/configs/nucleus2g/usbstorage/Make.defs +++ b/nuttx/configs/nucleus2g/usbstorage/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/olimex-lpc1766stk/README.txt b/nuttx/configs/olimex-lpc1766stk/README.txt index aaf40f9ff..a8bea4d0e 100644 --- a/nuttx/configs/olimex-lpc1766stk/README.txt +++ b/nuttx/configs/olimex-lpc1766stk/README.txt @@ -534,7 +534,7 @@ Using OpenOCD and GDB with an FT2232 JTAG emulator Once the OpenOCD daemon has been started, you can connect to it via GDB using the following GDB command: - arm-elf-gdb + arm-nuttx-elf-gdb (gdb) target remote localhost:3333 NOTE: The name of your GDB program may differ. For example, with the diff --git a/nuttx/configs/olimex-lpc1766stk/ftpc/Make.defs b/nuttx/configs/olimex-lpc1766stk/ftpc/Make.defs index 82cf0a2cd..5671fdffb 100644 --- a/nuttx/configs/olimex-lpc1766stk/ftpc/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/ftpc/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -123,7 +123,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/olimex-lpc1766stk/hidkbd/Make.defs b/nuttx/configs/olimex-lpc1766stk/hidkbd/Make.defs index dd9716814..1e7160c38 100644 --- a/nuttx/configs/olimex-lpc1766stk/hidkbd/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/hidkbd/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/olimex-lpc1766stk/nettest/Make.defs b/nuttx/configs/olimex-lpc1766stk/nettest/Make.defs index 634d97315..2502cf97b 100644 --- a/nuttx/configs/olimex-lpc1766stk/nettest/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/nettest/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/olimex-lpc1766stk/nsh/Make.defs b/nuttx/configs/olimex-lpc1766stk/nsh/Make.defs index af9750f40..7e62fd7fb 100644 --- a/nuttx/configs/olimex-lpc1766stk/nsh/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/nsh/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/olimex-lpc1766stk/nx/Make.defs b/nuttx/configs/olimex-lpc1766stk/nx/Make.defs index 685d827da..735e2bd0a 100644 --- a/nuttx/configs/olimex-lpc1766stk/nx/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/nx/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/olimex-lpc1766stk/ostest/Make.defs b/nuttx/configs/olimex-lpc1766stk/ostest/Make.defs index 84467ae64..7a9475761 100644 --- a/nuttx/configs/olimex-lpc1766stk/ostest/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/ostest/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/olimex-lpc1766stk/slip-httpd/Make.defs b/nuttx/configs/olimex-lpc1766stk/slip-httpd/Make.defs index 61b7f41e7..35d2c6480 100644 --- a/nuttx/configs/olimex-lpc1766stk/slip-httpd/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/slip-httpd/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -123,7 +123,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/olimex-lpc1766stk/thttpd/Make.defs b/nuttx/configs/olimex-lpc1766stk/thttpd/Make.defs index 0e37dbaa3..dbd84c2a6 100644 --- a/nuttx/configs/olimex-lpc1766stk/thttpd/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/thttpd/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -123,7 +123,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/olimex-lpc1766stk/usbserial/Make.defs b/nuttx/configs/olimex-lpc1766stk/usbserial/Make.defs index 7a56eb622..07cd41d46 100644 --- a/nuttx/configs/olimex-lpc1766stk/usbserial/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/usbserial/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/olimex-lpc1766stk/usbstorage/Make.defs b/nuttx/configs/olimex-lpc1766stk/usbstorage/Make.defs index 627cdd64e..76a6927ee 100644 --- a/nuttx/configs/olimex-lpc1766stk/usbstorage/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/usbstorage/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/olimex-lpc1766stk/wlan/Make.defs b/nuttx/configs/olimex-lpc1766stk/wlan/Make.defs index 1087fd8cc..0cc0d7edd 100644 --- a/nuttx/configs/olimex-lpc1766stk/wlan/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/wlan/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/olimex-lpc2378/nsh/Make.defs b/nuttx/configs/olimex-lpc2378/nsh/Make.defs index f81cfb448..2821aa73c 100644 --- a/nuttx/configs/olimex-lpc2378/nsh/Make.defs +++ b/nuttx/configs/olimex-lpc2378/nsh/Make.defs @@ -61,7 +61,7 @@ ifeq ($(CONFIG_OLIMEX_LPC2378_DEVKITARM),y) endif ifeq ($(CONFIG_OLIMEX_LPC2378_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- MAXOPTIMIZATION = -Os endif @@ -137,7 +137,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG),y) diff --git a/nuttx/configs/olimex-lpc2378/ostest/Make.defs b/nuttx/configs/olimex-lpc2378/ostest/Make.defs index d13e5eda0..69be8db5b 100644 --- a/nuttx/configs/olimex-lpc2378/ostest/Make.defs +++ b/nuttx/configs/olimex-lpc2378/ostest/Make.defs @@ -61,7 +61,7 @@ ifeq ($(CONFIG_OLIMEX_LPC2378_DEVKITARM),y) endif ifeq ($(CONFIG_OLIMEX_LPC2378_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- MAXOPTIMIZATION = -Os endif @@ -137,7 +137,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG),y) diff --git a/nuttx/configs/olimex-stm32-p107/nsh/Make.defs b/nuttx/configs/olimex-stm32-p107/nsh/Make.defs index a1a30f879..0108ef1ee 100644 --- a/nuttx/configs/olimex-stm32-p107/nsh/Make.defs +++ b/nuttx/configs/olimex-stm32-p107/nsh/Make.defs @@ -70,7 +70,7 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -132,7 +132,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/olimex-stm32-p107/ostest/Make.defs b/nuttx/configs/olimex-stm32-p107/ostest/Make.defs index 2e8cf87ac..7cf5e765f 100644 --- a/nuttx/configs/olimex-stm32-p107/ostest/Make.defs +++ b/nuttx/configs/olimex-stm32-p107/ostest/Make.defs @@ -70,7 +70,7 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -132,7 +132,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/olimex-strp711/README.txt b/nuttx/configs/olimex-strp711/README.txt index 955887d7b..74168dbfa 100644 --- a/nuttx/configs/olimex-strp711/README.txt +++ b/nuttx/configs/olimex-strp711/README.txt @@ -127,7 +127,7 @@ GNU Toolchain Options make # Will build for the NuttX buildroot toolchain make CROSSDEV=arm-eabi- # Will build for the devkitARM toolchain make CROSSDEV=arm-none-eabi- # Will build for the CodeSourcery toolchain - make CROSSDEV=arm-elf- # Will build for the NuttX buildroot toolchain + make CROSSDEV=arm-nuttx-elf- # Will build for the NuttX buildroot toolchain Of course, hard coding this CROSS_COMPILE value in Make.defs file will save some repetitive typing. @@ -267,7 +267,7 @@ GENERAL STEPS: 6. GDB - start arm-elf-gdb + start arm-nuttx-elf-gdb type 'file ' to load the executable type 'set debug remote 1' to enable tracing of gdb protocol (if required) type 'target remote localhost:3333' to connect to the target @@ -301,7 +301,7 @@ Windows OpenOCD will Olimex JTAG Once the OpenOCD daemon has been started, you can connect to it via GDB using the following GDB command: - arm-elf-gdb + arm-nuttx-elf-gdb (gdb) target remote localhost:3333 And you can load the NuttX ELF file into FLASH: diff --git a/nuttx/configs/olimex-strp711/nettest/Make.defs b/nuttx/configs/olimex-strp711/nettest/Make.defs index 9676e54fa..e4b8a9852 100644 --- a/nuttx/configs/olimex-strp711/nettest/Make.defs +++ b/nuttx/configs/olimex-strp711/nettest/Make.defs @@ -40,9 +40,9 @@ include ${TOPDIR}/tools/Config.mk # make -- Will build for the NuttX buildroot toolchain # make CROSSDEV=arm-eabi- -- Will build for the devkitARM toolchain # make CROSSDEV=arm-none-eabi- -- Will build for the CodeSourcery toolchain -# make CROSSDEV=arm-elf- -- Will build for the NuttX buildroot toolchain +# make CROSSDEV=arm-nuttx-elf- -- Will build for the NuttX buildroot toolchain -CROSSDEV = arm-elf- +CROSSDEV = arm-nuttx-elf- CC = $(CROSSDEV)gcc CXX = $(CROSSDEV)g++ CPP = $(CROSSDEV)gcc -E @@ -63,7 +63,7 @@ OBJCOPYARGS = -R .note -R .note.gnu.build-id -R .comment endif endif -ifeq ($(CROSSDEV),arm-elf-) +ifeq ($(CROSSDEV),arm-nuttx-elf-) MKDEP = $(TOPDIR)/tools/mkdeps.sh ARCHINCLUDES = -I. -isystem $(TOPDIR)/include ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx @@ -118,7 +118,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/olimex-strp711/nsh/Make.defs b/nuttx/configs/olimex-strp711/nsh/Make.defs index ad75862fa..9ef265d0e 100644 --- a/nuttx/configs/olimex-strp711/nsh/Make.defs +++ b/nuttx/configs/olimex-strp711/nsh/Make.defs @@ -40,9 +40,9 @@ include ${TOPDIR}/tools/Config.mk # make -- Will build for the NuttX buildroot toolchain # make CROSSDEV=arm-eabi- -- Will build for the devkitARM toolchain # make CROSSDEV=arm-none-eabi- -- Will build for the CodeSourcery toolchain -# make CROSSDEV=arm-elf- -- Will build for the NuttX buildroot toolchain +# make CROSSDEV=arm-nuttx-elf- -- Will build for the NuttX buildroot toolchain -CROSSDEV = arm-elf- +CROSSDEV = arm-nuttx-elf- CC = $(CROSSDEV)gcc CXX = $(CROSSDEV)g++ CPP = $(CROSSDEV)gcc -E @@ -63,7 +63,7 @@ OBJCOPYARGS = -R .note -R .note.gnu.build-id -R .comment endif endif -ifeq ($(CROSSDEV),arm-elf-) +ifeq ($(CROSSDEV),arm-nuttx-elf-) MKDEP = $(TOPDIR)/tools/mkdeps.sh ARCHINCLUDES = -I. -isystem $(TOPDIR)/include ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx @@ -118,7 +118,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/olimex-strp711/ostest/Make.defs b/nuttx/configs/olimex-strp711/ostest/Make.defs index 38fc7f5f2..f4bb09d99 100644 --- a/nuttx/configs/olimex-strp711/ostest/Make.defs +++ b/nuttx/configs/olimex-strp711/ostest/Make.defs @@ -40,9 +40,9 @@ include ${TOPDIR}/tools/Config.mk # make -- Will build for the NuttX buildroot toolchain # make CROSSDEV=arm-eabi- -- Will build for the devkitARM toolchain # make CROSSDEV=arm-none-eabi- -- Will build for the CodeSourcery toolchain -# make CROSSDEV=arm-elf- -- Will build for the NuttX buildroot toolchain +# make CROSSDEV=arm-nuttx-elf- -- Will build for the NuttX buildroot toolchain -CROSSDEV = arm-elf- +CROSSDEV = arm-nuttx-elf- CC = $(CROSSDEV)gcc CXX = $(CROSSDEV)g++ CPP = $(CROSSDEV)gcc -E @@ -63,7 +63,7 @@ OBJCOPYARGS = -R .note -R .note.gnu.build-id -R .comment endif endif -ifeq ($(CROSSDEV),arm-elf-) +ifeq ($(CROSSDEV),arm-nuttx-elf-) MKDEP = $(TOPDIR)/tools/mkdeps.sh ARCHINCLUDES = -I. -isystem $(TOPDIR)/include ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx @@ -118,7 +118,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/qemu-i486/nsh/Make.defs b/nuttx/configs/qemu-i486/nsh/Make.defs index c68d3d34e..8b5fe61f6 100644 --- a/nuttx/configs/qemu-i486/nsh/Make.defs +++ b/nuttx/configs/qemu-i486/nsh/Make.defs @@ -78,7 +78,7 @@ endif # Cygwin toolchains don't generate ELF binaries. ifeq ($(HOSTOS),Cygwin) -CROSSDEV = i486-elf- +CROSSDEV = i486-nuttx-elf- else CROSSDEV = endif diff --git a/nuttx/configs/qemu-i486/ostest/Make.defs b/nuttx/configs/qemu-i486/ostest/Make.defs index fa7dc7bf8..0a2423456 100644 --- a/nuttx/configs/qemu-i486/ostest/Make.defs +++ b/nuttx/configs/qemu-i486/ostest/Make.defs @@ -78,7 +78,7 @@ endif # Cygwin toolchains don't generate ELF binaries. ifeq ($(HOSTOS),Cygwin) -CROSSDEV = i486-elf- +CROSSDEV = i486-nuttx-elf- else CROSSDEV = endif diff --git a/nuttx/configs/sam3u-ek/knsh/Make.defs b/nuttx/configs/sam3u-ek/knsh/Make.defs index cce80669a..bbe8b23c0 100644 --- a/nuttx/configs/sam3u-ek/knsh/Make.defs +++ b/nuttx/configs/sam3u-ek/knsh/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_SAM3U_DEVKITARM),y) endif ifeq ($(CONFIG_SAM3U_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/sam3u-ek/nsh/Make.defs b/nuttx/configs/sam3u-ek/nsh/Make.defs index e4f24326d..0f236114f 100644 --- a/nuttx/configs/sam3u-ek/nsh/Make.defs +++ b/nuttx/configs/sam3u-ek/nsh/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_SAM3U_DEVKITARM),y) endif ifeq ($(CONFIG_SAM3U_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/sam3u-ek/nx/Make.defs b/nuttx/configs/sam3u-ek/nx/Make.defs index e98aaf9d6..10cabe5a5 100644 --- a/nuttx/configs/sam3u-ek/nx/Make.defs +++ b/nuttx/configs/sam3u-ek/nx/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_SAM3U_DEVKITARM),y) endif ifeq ($(CONFIG_SAM3U_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/sam3u-ek/ostest/Make.defs b/nuttx/configs/sam3u-ek/ostest/Make.defs index 7d38aedb2..7689fb2a1 100644 --- a/nuttx/configs/sam3u-ek/ostest/Make.defs +++ b/nuttx/configs/sam3u-ek/ostest/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_SAM3U_DEVKITARM),y) endif ifeq ($(CONFIG_SAM3U_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/sam3u-ek/touchscreen/Make.defs b/nuttx/configs/sam3u-ek/touchscreen/Make.defs index 1dccbc6bc..2047daf68 100644 --- a/nuttx/configs/sam3u-ek/touchscreen/Make.defs +++ b/nuttx/configs/sam3u-ek/touchscreen/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_SAM3U_DEVKITARM),y) endif ifeq ($(CONFIG_SAM3U_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/shenzhou/nsh/Make.defs b/nuttx/configs/shenzhou/nsh/Make.defs index 847866420..95495d4c4 100644 --- a/nuttx/configs/shenzhou/nsh/Make.defs +++ b/nuttx/configs/shenzhou/nsh/Make.defs @@ -82,8 +82,8 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- - ARCROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- + ARCROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -153,7 +153,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/shenzhou/nxwm/Make.defs b/nuttx/configs/shenzhou/nxwm/Make.defs index 0025282b4..96e0ffd4b 100644 --- a/nuttx/configs/shenzhou/nxwm/Make.defs +++ b/nuttx/configs/shenzhou/nxwm/Make.defs @@ -82,8 +82,8 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- - ARCROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- + ARCROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -153,7 +153,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/skp16c26/README.txt b/nuttx/configs/skp16c26/README.txt index dc94bbf8d..31332b59b 100644 --- a/nuttx/configs/skp16c26/README.txt +++ b/nuttx/configs/skp16c26/README.txt @@ -1,112 +1,112 @@ -configs/skp16c26/README.txt -^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -1. The buildroot package can be used to build an M16C toolchain. The toolchain - buildroot can be downloaded from misc/buildroot in the NuttX SVN. Insructions - for building the toolchain are provided below. - - However, the target cannot be built because the GNU m16c-elf-ld link fails with - the following message: - - m32c-elf-ld: BFD (GNU Binutils) 2.19 assertion fail /home/Owner/projects/nuttx/buildroot/toolchain_build_m32c/binutils-2.19/bfd/elf32-m32c.c:482 - - Where the reference line is: - - /* If the symbol is out of range for a 16-bit address, - we must have allocated a plt entry. */ - BFD_ASSERT (*plt_offset != (bfd_vma) -1); - - No workaround is known at this time. This is a show stopper for M16C. - -2. A supported version of the M16C toolchain is available here: - - http://www.kpitgnutools.com/index.php - - This download is free but requires registration. Unfortunately, this v0901 of - this toolchain shows the same behavior: - - c:\Hew3\Tools\KPIT Cummins\GNUM16CM32C-ELF\v0901\m32c-elf\bin\m32c-elf-ld.exe: BFD (GNU Binutils) 2.19-GNUM16CM32C_v0901 assertion fail /home/kpit/fsfsrc/binutils-2.19/bfd/elf32-m32c.c:482 - -It is possible that this error messasge my be telling me -- a very roundabout way -- -that I have exceeded the FLASH region, but I think that unlikely (it is difficult -to know if the link does not complete gracefully). - -BUILDING THE R8C/M16C/M32C GNU TOOLCHAIN USING BUILDROOT -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -NOTE: See the toolchain issues above -- you may not want to waste your time. - -1. CD to the correct directory. - - Change to the directory just above the NuttX installation. If is - where NuttX is installed, then cd to /.. - -2. Get and Install the buildroot Module - - a. Using a release tarball: - - cd /.. - Download the appropriate buildroot package. - unpack the buildroot package - rename the directory to buildroot - - b. Using SVN - - Check out the misc/buildroot module. SVN checkout instructions: - - svn checkout svn://svn.code.sf.net/p/nuttx/code/trunk/buildroot buildroot - - Make the archive directory: - - mkdir archive - - The /../buildroot is where the toolchain is built; - The /../archive directory is where toolchain sources will be downloaded. - -3. Make sure that NuttX is configured - - cd /tools - ./configure.sh - -4. Configure and Make the buildroot - - cd buildroot - cp configs/m32c-defconfig-4.2.4 .config - make oldconfig - make - - This will download the large source packages for the toolchain and build the toolchain. - The resulting binaries will be under buildroot/build_m32c. There will also be a - large build directory called toolchain_build_m32c; this directory can be removed once - the build completes successfully. - -Cygwin GCC BUILD NOTES -^^^^^^^^^^^^^^^^^^^^^^ - On Cygwin, the buildroot 'make' command will fail with an error like: - - "... - build/genchecksum cc1-dummy > cc1-checksum.c - opening cc1-dummy: No such file or directory - ..." - - This is caused because on Cygwin, host executables will be generated with the extension .exe - and, apparently, the make variable "exeext" is set incorrectly. A work around after the - above occurs is: - - cd toolchain_build_m32c/gcc-4.2.4-initial/gcc # Go to the directory where error occurred - mv cc1-dummy.exe cc1-dummy # Rename the executable without .exe - rm cc1-checksum.c # Get rid of the bad generated file - - Then resume the buildroot make: - - cd - # Back to the buildroot make directory - make # Restart the build - - GCC is built twice. First a initial, "bootstap" GCC is produced in - toolchain_build_m32c/gcc-4.2.4-initial, then the final GCC is produced in - toolchain_build_m32c/gcc-4.2.4-final. The above error will occur twice: Once for - the intial GCC build (see above) and once for the final GCC build. For the final GCC - build, the workaround is the same except that the directory will be - toolchain_build_m32c/gcc-4.2.4-final/gcc. - - \ No newline at end of file +configs/skp16c26/README.txt +^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1. The buildroot package can be used to build an M16C toolchain. The toolchain + buildroot can be downloaded from misc/buildroot in the NuttX SVN. Insructions + for building the toolchain are provided below. + + However, the target cannot be built because the GNU m16c-nuttx-elf-ld link fails with + the following message: + + m32c-nuttx-elf-ld: BFD (GNU Binutils) 2.19 assertion fail /home/Owner/projects/nuttx/buildroot/toolchain_build_m32c/binutils-2.19/bfd/elf32-m32c.c:482 + + Where the reference line is: + + /* If the symbol is out of range for a 16-bit address, + we must have allocated a plt entry. */ + BFD_ASSERT (*plt_offset != (bfd_vma) -1); + + No workaround is known at this time. This is a show stopper for M16C. + +2. A supported version of the M16C toolchain is available here: + + http://www.kpitgnutools.com/index.php + + This download is free but requires registration. Unfortunately, this v0901 of + this toolchain shows the same behavior: + + c:\Hew3\Tools\KPIT Cummins\GNUM16CM32C-ELF\v0901\m32c-elf\bin\m32c-elf-ld.exe: BFD (GNU Binutils) 2.19-GNUM16CM32C_v0901 assertion fail /home/kpit/fsfsrc/binutils-2.19/bfd/elf32-m32c.c:482 + +It is possible that this error messasge my be telling me -- a very roundabout way -- +that I have exceeded the FLASH region, but I think that unlikely (it is difficult +to know if the link does not complete gracefully). + +BUILDING THE R8C/M16C/M32C GNU TOOLCHAIN USING BUILDROOT +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +NOTE: See the toolchain issues above -- you may not want to waste your time. + +1. CD to the correct directory. + + Change to the directory just above the NuttX installation. If is + where NuttX is installed, then cd to /.. + +2. Get and Install the buildroot Module + + a. Using a release tarball: + + cd /.. + Download the appropriate buildroot package. + unpack the buildroot package + rename the directory to buildroot + + b. Using SVN + + Check out the misc/buildroot module. SVN checkout instructions: + + svn checkout svn://svn.code.sf.net/p/nuttx/code/trunk/buildroot buildroot + + Make the archive directory: + + mkdir archive + + The /../buildroot is where the toolchain is built; + The /../archive directory is where toolchain sources will be downloaded. + +3. Make sure that NuttX is configured + + cd /tools + ./configure.sh + +4. Configure and Make the buildroot + + cd buildroot + cp configs/m32c-defconfig-4.2.4 .config + make oldconfig + make + + This will download the large source packages for the toolchain and build the toolchain. + The resulting binaries will be under buildroot/build_m32c. There will also be a + large build directory called toolchain_build_m32c; this directory can be removed once + the build completes successfully. + +Cygwin GCC BUILD NOTES +^^^^^^^^^^^^^^^^^^^^^^ + On Cygwin, the buildroot 'make' command will fail with an error like: + + "... + build/genchecksum cc1-dummy > cc1-checksum.c + opening cc1-dummy: No such file or directory + ..." + + This is caused because on Cygwin, host executables will be generated with the extension .exe + and, apparently, the make variable "exeext" is set incorrectly. A work around after the + above occurs is: + + cd toolchain_build_m32c/gcc-4.2.4-initial/gcc # Go to the directory where error occurred + mv cc1-dummy.exe cc1-dummy # Rename the executable without .exe + rm cc1-checksum.c # Get rid of the bad generated file + + Then resume the buildroot make: + + cd - # Back to the buildroot make directory + make # Restart the build + + GCC is built twice. First a initial, "bootstap" GCC is produced in + toolchain_build_m32c/gcc-4.2.4-initial, then the final GCC is produced in + toolchain_build_m32c/gcc-4.2.4-final. The above error will occur twice: Once for + the intial GCC build (see above) and once for the final GCC build. For the final GCC + build, the workaround is the same except that the directory will be + toolchain_build_m32c/gcc-4.2.4-final/gcc. + + diff --git a/nuttx/configs/skp16c26/ostest/Make.defs b/nuttx/configs/skp16c26/ostest/Make.defs index 79f014013..a7444daae 100644 --- a/nuttx/configs/skp16c26/ostest/Make.defs +++ b/nuttx/configs/skp16c26/ostest/Make.defs @@ -36,7 +36,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk -CROSSDEV = m32c-elf- +CROSSDEV = m32c-nuttx-elf- CC = $(CROSSDEV)gcc CPP = $(CROSSDEV)gcc -E LD = $(CROSSDEV)ld diff --git a/nuttx/configs/stm3210e-eval/RIDE/Make.defs b/nuttx/configs/stm3210e-eval/RIDE/Make.defs index f24075038..dfd0f600b 100644 --- a/nuttx/configs/stm3210e-eval/RIDE/Make.defs +++ b/nuttx/configs/stm3210e-eval/RIDE/Make.defs @@ -70,7 +70,7 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -132,7 +132,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm3210e-eval/buttons/Make.defs b/nuttx/configs/stm3210e-eval/buttons/Make.defs index ed7d6e7f0..9f0691bba 100644 --- a/nuttx/configs/stm3210e-eval/buttons/Make.defs +++ b/nuttx/configs/stm3210e-eval/buttons/Make.defs @@ -70,7 +70,7 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -132,7 +132,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm3210e-eval/composite/Make.defs b/nuttx/configs/stm3210e-eval/composite/Make.defs index e08466429..9b855671f 100644 --- a/nuttx/configs/stm3210e-eval/composite/Make.defs +++ b/nuttx/configs/stm3210e-eval/composite/Make.defs @@ -70,7 +70,7 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -132,7 +132,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm3210e-eval/nsh/Make.defs b/nuttx/configs/stm3210e-eval/nsh/Make.defs index 1e8e945b6..afdf0c097 100644 --- a/nuttx/configs/stm3210e-eval/nsh/Make.defs +++ b/nuttx/configs/stm3210e-eval/nsh/Make.defs @@ -70,7 +70,7 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -132,7 +132,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm3210e-eval/nsh2/Make.defs b/nuttx/configs/stm3210e-eval/nsh2/Make.defs index 049c9d7a8..7d36c9a00 100644 --- a/nuttx/configs/stm3210e-eval/nsh2/Make.defs +++ b/nuttx/configs/stm3210e-eval/nsh2/Make.defs @@ -70,7 +70,7 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -132,7 +132,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm3210e-eval/nx/Make.defs b/nuttx/configs/stm3210e-eval/nx/Make.defs index a553e0163..bb0ba5b6d 100644 --- a/nuttx/configs/stm3210e-eval/nx/Make.defs +++ b/nuttx/configs/stm3210e-eval/nx/Make.defs @@ -70,7 +70,7 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -132,7 +132,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm3210e-eval/nxconsole/Make.defs b/nuttx/configs/stm3210e-eval/nxconsole/Make.defs index d55f4c61d..84b36b267 100644 --- a/nuttx/configs/stm3210e-eval/nxconsole/Make.defs +++ b/nuttx/configs/stm3210e-eval/nxconsole/Make.defs @@ -73,7 +73,7 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -134,7 +134,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm3210e-eval/nxlines/Make.defs b/nuttx/configs/stm3210e-eval/nxlines/Make.defs index 83bd9eb5e..a896a901e 100644 --- a/nuttx/configs/stm3210e-eval/nxlines/Make.defs +++ b/nuttx/configs/stm3210e-eval/nxlines/Make.defs @@ -73,7 +73,7 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -134,7 +134,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm3210e-eval/nxtext/Make.defs b/nuttx/configs/stm3210e-eval/nxtext/Make.defs index 4a082fc74..00370c3b0 100644 --- a/nuttx/configs/stm3210e-eval/nxtext/Make.defs +++ b/nuttx/configs/stm3210e-eval/nxtext/Make.defs @@ -73,7 +73,7 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -134,7 +134,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm3210e-eval/ostest/Make.defs b/nuttx/configs/stm3210e-eval/ostest/Make.defs index 41a197457..09b3f0395 100644 --- a/nuttx/configs/stm3210e-eval/ostest/Make.defs +++ b/nuttx/configs/stm3210e-eval/ostest/Make.defs @@ -70,7 +70,7 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -132,7 +132,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm3210e-eval/pm/Make.defs b/nuttx/configs/stm3210e-eval/pm/Make.defs index c298c4364..0cc96fa4e 100644 --- a/nuttx/configs/stm3210e-eval/pm/Make.defs +++ b/nuttx/configs/stm3210e-eval/pm/Make.defs @@ -70,7 +70,7 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -132,7 +132,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm3210e-eval/usbserial/Make.defs b/nuttx/configs/stm3210e-eval/usbserial/Make.defs index f45de369e..cda6edf4e 100644 --- a/nuttx/configs/stm3210e-eval/usbserial/Make.defs +++ b/nuttx/configs/stm3210e-eval/usbserial/Make.defs @@ -70,7 +70,7 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -132,7 +132,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm3210e-eval/usbstorage/Make.defs b/nuttx/configs/stm3210e-eval/usbstorage/Make.defs index e0a4de6f9..36688bc80 100644 --- a/nuttx/configs/stm3210e-eval/usbstorage/Make.defs +++ b/nuttx/configs/stm3210e-eval/usbstorage/Make.defs @@ -70,7 +70,7 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -132,7 +132,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm3220g-eval/dhcpd/Make.defs b/nuttx/configs/stm3220g-eval/dhcpd/Make.defs index 4a94997a5..f75e94501 100644 --- a/nuttx/configs/stm3220g-eval/dhcpd/Make.defs +++ b/nuttx/configs/stm3220g-eval/dhcpd/Make.defs @@ -90,8 +90,8 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- - ARCROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- + ARCROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -155,7 +155,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm3220g-eval/nettest/Make.defs b/nuttx/configs/stm3220g-eval/nettest/Make.defs index c69852119..f307d9475 100644 --- a/nuttx/configs/stm3220g-eval/nettest/Make.defs +++ b/nuttx/configs/stm3220g-eval/nettest/Make.defs @@ -90,8 +90,8 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- - ARCROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- + ARCROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -155,7 +155,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm3220g-eval/nsh/Make.defs b/nuttx/configs/stm3220g-eval/nsh/Make.defs index 4b2bbef30..9fe8b0ffa 100644 --- a/nuttx/configs/stm3220g-eval/nsh/Make.defs +++ b/nuttx/configs/stm3220g-eval/nsh/Make.defs @@ -90,8 +90,8 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- - ARCROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- + ARCROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -155,7 +155,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm3220g-eval/nsh2/Make.defs b/nuttx/configs/stm3220g-eval/nsh2/Make.defs index d81350868..64f158ecb 100644 --- a/nuttx/configs/stm3220g-eval/nsh2/Make.defs +++ b/nuttx/configs/stm3220g-eval/nsh2/Make.defs @@ -90,8 +90,8 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- - ARCROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- + ARCROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -155,7 +155,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm3220g-eval/nxwm/Make.defs b/nuttx/configs/stm3220g-eval/nxwm/Make.defs index 616529e7e..37280e0c4 100644 --- a/nuttx/configs/stm3220g-eval/nxwm/Make.defs +++ b/nuttx/configs/stm3220g-eval/nxwm/Make.defs @@ -90,8 +90,8 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- - ARCROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- + ARCROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -155,7 +155,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm3220g-eval/ostest/Make.defs b/nuttx/configs/stm3220g-eval/ostest/Make.defs index 9d8c07dfa..41e8fff14 100644 --- a/nuttx/configs/stm3220g-eval/ostest/Make.defs +++ b/nuttx/configs/stm3220g-eval/ostest/Make.defs @@ -90,8 +90,8 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- - ARCROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- + ARCROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -155,7 +155,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm3220g-eval/telnetd/Make.defs b/nuttx/configs/stm3220g-eval/telnetd/Make.defs index 10725d727..416bfaa47 100644 --- a/nuttx/configs/stm3220g-eval/telnetd/Make.defs +++ b/nuttx/configs/stm3220g-eval/telnetd/Make.defs @@ -90,8 +90,8 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- - ARCROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- + ARCROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -155,7 +155,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm3240g-eval/dhcpd/Make.defs b/nuttx/configs/stm3240g-eval/dhcpd/Make.defs index 7fb1e0b7f..1c7a7cff0 100644 --- a/nuttx/configs/stm3240g-eval/dhcpd/Make.defs +++ b/nuttx/configs/stm3240g-eval/dhcpd/Make.defs @@ -90,8 +90,8 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- - ARCROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- + ARCROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -155,7 +155,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm3240g-eval/discover/Make.defs b/nuttx/configs/stm3240g-eval/discover/Make.defs index abcae0f5f..9cf9d5958 100644 --- a/nuttx/configs/stm3240g-eval/discover/Make.defs +++ b/nuttx/configs/stm3240g-eval/discover/Make.defs @@ -90,8 +90,8 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- - ARCROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- + ARCROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -155,7 +155,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm3240g-eval/nettest/Make.defs b/nuttx/configs/stm3240g-eval/nettest/Make.defs index a0a1cd58f..e8af4cbb5 100644 --- a/nuttx/configs/stm3240g-eval/nettest/Make.defs +++ b/nuttx/configs/stm3240g-eval/nettest/Make.defs @@ -90,8 +90,8 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- - ARCROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- + ARCROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -155,7 +155,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm3240g-eval/nsh/Make.defs b/nuttx/configs/stm3240g-eval/nsh/Make.defs index ab0ede05e..e88f1054b 100644 --- a/nuttx/configs/stm3240g-eval/nsh/Make.defs +++ b/nuttx/configs/stm3240g-eval/nsh/Make.defs @@ -90,8 +90,8 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- - ARCROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- + ARCROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -155,7 +155,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm3240g-eval/nsh2/Make.defs b/nuttx/configs/stm3240g-eval/nsh2/Make.defs index 7a0e19582..3e7fa8bd2 100644 --- a/nuttx/configs/stm3240g-eval/nsh2/Make.defs +++ b/nuttx/configs/stm3240g-eval/nsh2/Make.defs @@ -90,8 +90,8 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- - ARCROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- + ARCROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -155,7 +155,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm3240g-eval/nxconsole/Make.defs b/nuttx/configs/stm3240g-eval/nxconsole/Make.defs index 6c200d3ce..aedfacc80 100644 --- a/nuttx/configs/stm3240g-eval/nxconsole/Make.defs +++ b/nuttx/configs/stm3240g-eval/nxconsole/Make.defs @@ -90,8 +90,8 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- - ARCROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- + ARCROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -155,7 +155,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm3240g-eval/nxwm/Make.defs b/nuttx/configs/stm3240g-eval/nxwm/Make.defs index 167792094..631cfab86 100644 --- a/nuttx/configs/stm3240g-eval/nxwm/Make.defs +++ b/nuttx/configs/stm3240g-eval/nxwm/Make.defs @@ -90,8 +90,8 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- - ARCROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- + ARCROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -155,7 +155,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm3240g-eval/ostest/Make.defs b/nuttx/configs/stm3240g-eval/ostest/Make.defs index a7e7a1392..875d39f22 100644 --- a/nuttx/configs/stm3240g-eval/ostest/Make.defs +++ b/nuttx/configs/stm3240g-eval/ostest/Make.defs @@ -90,8 +90,8 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- - ARCROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- + ARCROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -155,7 +155,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm3240g-eval/telnetd/Make.defs b/nuttx/configs/stm3240g-eval/telnetd/Make.defs index 1ddbddaab..d0ed37f28 100644 --- a/nuttx/configs/stm3240g-eval/telnetd/Make.defs +++ b/nuttx/configs/stm3240g-eval/telnetd/Make.defs @@ -90,8 +90,8 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- - ARCROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- + ARCROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -155,7 +155,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm3240g-eval/webserver/Make.defs b/nuttx/configs/stm3240g-eval/webserver/Make.defs index 066935080..fbe1ffb0e 100644 --- a/nuttx/configs/stm3240g-eval/webserver/Make.defs +++ b/nuttx/configs/stm3240g-eval/webserver/Make.defs @@ -89,8 +89,8 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- - ARCROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- + ARCROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -154,7 +154,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm3240g-eval/xmlrpc/Make.defs b/nuttx/configs/stm3240g-eval/xmlrpc/Make.defs index eb02622e6..61b0d5c4e 100644 --- a/nuttx/configs/stm3240g-eval/xmlrpc/Make.defs +++ b/nuttx/configs/stm3240g-eval/xmlrpc/Make.defs @@ -90,8 +90,8 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- - ARCROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- + ARCROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -155,7 +155,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm32f4discovery/nsh/Make.defs b/nuttx/configs/stm32f4discovery/nsh/Make.defs index 4a776bffe..f4110cce3 100644 --- a/nuttx/configs/stm32f4discovery/nsh/Make.defs +++ b/nuttx/configs/stm32f4discovery/nsh/Make.defs @@ -90,8 +90,8 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- - ARCROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- + ARCROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -155,7 +155,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm32f4discovery/nxlines/Make.defs b/nuttx/configs/stm32f4discovery/nxlines/Make.defs index c728da7b3..8dab2009c 100644 --- a/nuttx/configs/stm32f4discovery/nxlines/Make.defs +++ b/nuttx/configs/stm32f4discovery/nxlines/Make.defs @@ -90,8 +90,8 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- - ARCROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- + ARCROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -155,7 +155,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm32f4discovery/ostest/Make.defs b/nuttx/configs/stm32f4discovery/ostest/Make.defs index 7ee437589..f20fddb84 100644 --- a/nuttx/configs/stm32f4discovery/ostest/Make.defs +++ b/nuttx/configs/stm32f4discovery/ostest/Make.defs @@ -90,8 +90,8 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- - ARCROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- + ARCROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -155,7 +155,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/stm32f4discovery/pm/Make.defs b/nuttx/configs/stm32f4discovery/pm/Make.defs index 8dc63684e..f96f439ee 100644 --- a/nuttx/configs/stm32f4discovery/pm/Make.defs +++ b/nuttx/configs/stm32f4discovery/pm/Make.defs @@ -90,8 +90,8 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- - ARCROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- + ARCROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -155,7 +155,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/teensy/hello/Make.defs b/nuttx/configs/teensy/hello/Make.defs index 72d51de14..cca88363c 100644 --- a/nuttx/configs/teensy/hello/Make.defs +++ b/nuttx/configs/teensy/hello/Make.defs @@ -57,7 +57,7 @@ endif ifeq ($(CONFIG_AVR_BUILDROOT),y) # NuttX buildroot GCC toolchain under Linux or Cygwin - CROSSDEV = avr-elf- + CROSSDEV = avr-nuttx-elf- MAXOPTIMIZATION = -O2 ARCHCPUFLAGS = -mmcu=at90usb1286 LDFLAGS += -nostartfiles -nodefaultlibs diff --git a/nuttx/configs/teensy/nsh/Make.defs b/nuttx/configs/teensy/nsh/Make.defs index e58b1596e..13f8e7902 100644 --- a/nuttx/configs/teensy/nsh/Make.defs +++ b/nuttx/configs/teensy/nsh/Make.defs @@ -57,7 +57,7 @@ endif ifeq ($(CONFIG_AVR_BUILDROOT),y) # NuttX buildroot GCC toolchain under Linux or Cygwin - CROSSDEV = avr-elf- + CROSSDEV = avr-nuttx-elf- MAXOPTIMIZATION = -O2 ARCHCPUFLAGS = -mmcu=at90usb1286 LDFLAGS += -nostartfiles -nodefaultlibs diff --git a/nuttx/configs/teensy/usbstorage/Make.defs b/nuttx/configs/teensy/usbstorage/Make.defs index b221491d6..706daf81f 100644 --- a/nuttx/configs/teensy/usbstorage/Make.defs +++ b/nuttx/configs/teensy/usbstorage/Make.defs @@ -57,7 +57,7 @@ endif ifeq ($(CONFIG_AVR_BUILDROOT),y) # NuttX buildroot GCC toolchain under Linux or Cygwin - CROSSDEV = avr-elf- + CROSSDEV = avr-nuttx-elf- MAXOPTIMIZATION = -O2 ARCHCPUFLAGS = -mmcu=at90usb1286 LDFLAGS += -nostartfiles -nodefaultlibs diff --git a/nuttx/configs/twr-k60n512/nsh/Make.defs b/nuttx/configs/twr-k60n512/nsh/Make.defs index ebeea90a5..99041bcc2 100644 --- a/nuttx/configs/twr-k60n512/nsh/Make.defs +++ b/nuttx/configs/twr-k60n512/nsh/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_KINETIS_DEVKITARM),y) endif ifeq ($(CONFIG_KINETIS_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft -mlong-calls MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/twr-k60n512/ostest/Make.defs b/nuttx/configs/twr-k60n512/ostest/Make.defs index 2f5e208fe..93c887a2d 100644 --- a/nuttx/configs/twr-k60n512/ostest/Make.defs +++ b/nuttx/configs/twr-k60n512/ostest/Make.defs @@ -58,7 +58,7 @@ ifeq ($(CONFIG_KINETIS_DEVKITARM),y) endif ifeq ($(CONFIG_KINETIS_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft -mlong-calls MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/us7032evb1/nsh/Make.defs b/nuttx/configs/us7032evb1/nsh/Make.defs index d861f5d48..9cbc41f5b 100644 --- a/nuttx/configs/us7032evb1/nsh/Make.defs +++ b/nuttx/configs/us7032evb1/nsh/Make.defs @@ -50,7 +50,7 @@ ARCHDEFINES = ARCHINCLUDES = -I. -isystem $(TOPDIR)/include ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nsh/ld.script -CROSSDEV = sh-elf- +CROSSDEV = sh-nuttx-elf- CC = $(CROSSDEV)gcc CPP = $(CROSSDEV)gcc -E LD = $(CROSSDEV)ld diff --git a/nuttx/configs/us7032evb1/ostest/Make.defs b/nuttx/configs/us7032evb1/ostest/Make.defs index 580c12628..32f45edda 100644 --- a/nuttx/configs/us7032evb1/ostest/Make.defs +++ b/nuttx/configs/us7032evb1/ostest/Make.defs @@ -50,7 +50,7 @@ ARCHDEFINES = ARCHINCLUDES = -I. -isystem $(TOPDIR)/include ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/ostest/ld.script -CROSSDEV = sh-elf- +CROSSDEV = sh-nuttx-elf- CC = $(CROSSDEV)gcc CPP = $(CROSSDEV)gcc -E LD = $(CROSSDEV)ld diff --git a/nuttx/configs/vsn/nsh/Make.defs b/nuttx/configs/vsn/nsh/Make.defs index 15de85f60..abcdf49c1 100644 --- a/nuttx/configs/vsn/nsh/Make.defs +++ b/nuttx/configs/vsn/nsh/Make.defs @@ -70,7 +70,7 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-elf- + CROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -132,7 +132,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-elf-) +ifneq ($(CROSSDEV),arm-nuttx-elf-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) -- cgit v1.2.3 From 535398581c4c7fe105089270f2497247b5279acd Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 5 Oct 2012 23:43:05 +0000 Subject: configs/shenzhou will now use the 4.6.3 buildroot EABI toolchain git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5214 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 5 +++++ nuttx/configs/shenzhou/README.txt | 4 ++-- nuttx/configs/shenzhou/nsh/Make.defs | 6 +++--- nuttx/configs/shenzhou/nxwm/Make.defs | 6 +++--- 4 files changed, 13 insertions(+), 8 deletions(-) (limited to 'nuttx') diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 257119a35..7121c506f 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3465,3 +3465,8 @@ of CONFIG_EXAMPLE_* to CONFIG_EXAMPLES_*. * drivers/mtd/w25.c and configs/*/src/up_w25.c: Several fixes for the W25 SPI FLASH. + * configs/*/Make.defs: All buildroot tools now use the extension + xxx-nuttx-elf- vs. xxx-elf- + * configs/shenzhou/*/Make.defs: Now uses the new buildroot 4.6.3 + EABI toolchain. + diff --git a/nuttx/configs/shenzhou/README.txt b/nuttx/configs/shenzhou/README.txt index 1f3f254aa..cad0ad2e7 100644 --- a/nuttx/configs/shenzhou/README.txt +++ b/nuttx/configs/shenzhou/README.txt @@ -354,7 +354,7 @@ NuttX buildroot Toolchain 4. cd /buildroot - 5. cp configs/cortexm3-defconfig-4.3.3 .config + 5. cp configs/cortexm3-eabi-defconfig-4.6.3 .config 6. make oldconfig @@ -770,4 +770,4 @@ Where is one of the following: -CONFIG_NX_WRITEONLY=y +# CONFIG_NX_WRITEONLY is not set - \ No newline at end of file + diff --git a/nuttx/configs/shenzhou/nsh/Make.defs b/nuttx/configs/shenzhou/nsh/Make.defs index 95495d4c4..317a95cda 100644 --- a/nuttx/configs/shenzhou/nsh/Make.defs +++ b/nuttx/configs/shenzhou/nsh/Make.defs @@ -82,8 +82,8 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCROSSDEV = arm-nuttx-elf- + CROSSDEV = arm-nuttx-eabi- + ARCROSSDEV = arm-nuttx-eabi- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -153,7 +153,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-nuttx-elf-) +ifneq ($(CROSSDEV),arm-nuttx-eabi-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/shenzhou/nxwm/Make.defs b/nuttx/configs/shenzhou/nxwm/Make.defs index 96e0ffd4b..96104d6d0 100644 --- a/nuttx/configs/shenzhou/nxwm/Make.defs +++ b/nuttx/configs/shenzhou/nxwm/Make.defs @@ -82,8 +82,8 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCROSSDEV = arm-nuttx-elf- + CROSSDEV = arm-nuttx-eabi- + ARCROSSDEV = arm-nuttx-eabi- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -153,7 +153,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CROSSDEV),arm-nuttx-elf-) +ifneq ($(CROSSDEV),arm-nuttx-eabi-) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) -- cgit v1.2.3 From b9454627bc2b5ae8383cffdf5ae612e03354c2a1 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 6 Oct 2012 00:20:49 +0000 Subject: More changes for buildroot EABI toolchain git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5215 42af7a65-404d-4744-a932-0658087f49c3 --- misc/buildroot/configs/README.txt | 10 +++++++--- misc/buildroot/configs/arm920t-eabi-defconfig-4.5.2 | 2 +- misc/buildroot/configs/arm926t-defconfig-4.3.3 | 2 +- misc/buildroot/configs/arm926t-defconfig-nxflat | 2 +- nuttx/configs/shenzhou/README.txt | 17 ++++++++++++++++- nuttx/configs/shenzhou/nsh/Make.defs | 3 ++- nuttx/configs/shenzhou/nxwm/Make.defs | 3 ++- 7 files changed, 30 insertions(+), 9 deletions(-) (limited to 'nuttx') diff --git a/misc/buildroot/configs/README.txt b/misc/buildroot/configs/README.txt index f37bcf178..6b76ff80d 100644 --- a/misc/buildroot/configs/README.txt +++ b/misc/buildroot/configs/README.txt @@ -14,12 +14,12 @@ AVAILABLE CONFIGURATIONS ^^^^^^^^^^^^^^^^^^^^^^^^ arm-defconfig - Builds an ARM toolchain using gcc 3.4.6 + Builds an OABI ARM toolchain using gcc 3.4.6 arm7tdmi-defconfig-4.2.4 arm920t-defconfig-4.2.4 arm926t-defconfig-4.2.4 - Builds an ARM toolchain using gcc 4.2.4. This configuration + Builds an OABI ARM toolchain using gcc 4.2.4. This configuration builds both gcc and g++. There are three versions: one for arm7tdmi (armv4t), arm920t (armv4t) and arm926t (arv5t) because of differences in the way that soft floating is handled in between @@ -48,7 +48,7 @@ arm926t-defconfig-4.2.4 arm920t-defconfig-4.3.3 arm7tdmi-defconfig-4.3.3 - Builds an ARM toolchain using gcc 4.3.3. These configurations + Builds an OABI ARM toolchain using gcc 4.3.3. These configurations builds both gcc and g++ for the arm7tdmi (armv4t) or the arm920t (armv4t). These are udates to *-defconfig-4.2.4 (see notes above). @@ -62,6 +62,10 @@ cortexm3-defconfig-4.3.3 Builds an OABI ARM toolchain for the Cortex-M3 using gcc 4.3.3. This configuration builds gcc, g++ and the NXFLAT toolchain. +cortexm3-eabi-defconfig-4.6.3 + Builds an EABI ARM toolchain for the Cortex-M3 using gcc 4.6.3. + This configuration builds gcc, g++ and the NXFLAT toolchain. + cortexm3-defconfig-nxflat arm926t-defconfig-nxflat This configuration build an NXFLAT toolchain (only) for diff --git a/misc/buildroot/configs/arm920t-eabi-defconfig-4.5.2 b/misc/buildroot/configs/arm920t-eabi-defconfig-4.5.2 index 3586e4f33..6e55dc363 100644 --- a/misc/buildroot/configs/arm920t-eabi-defconfig-4.5.2 +++ b/misc/buildroot/configs/arm920t-eabi-defconfig-4.5.2 @@ -61,7 +61,7 @@ BR2_NUTTX_DIR="$(TOPDIR)/../../nuttx" BR2_TOPDIR_PREFIX="" BR2_TOPDIR_SUFFIX="" BR2_GNU_BUILD_SUFFIX="pc-elf" -BR2_GNU_TARGET_SUFFIX="eabi" +BR2_GNU_TARGET_SUFFIX="nuttx-eabi" # BR2_PREFER_IMA is not set # diff --git a/misc/buildroot/configs/arm926t-defconfig-4.3.3 b/misc/buildroot/configs/arm926t-defconfig-4.3.3 index b72a12451..1d6301779 100644 --- a/misc/buildroot/configs/arm926t-defconfig-4.3.3 +++ b/misc/buildroot/configs/arm926t-defconfig-4.3.3 @@ -59,7 +59,7 @@ BR2_STAGING_DIR="$(BUILD_DIR)/staging_dir" BR2_NUTTX_DIR="$(TOPDIR)/../../nuttx" BR2_TOPDIR_PREFIX="" BR2_TOPDIR_SUFFIX="" -BR2_GNU_BUILD_SUFFIX="arm-elf" +BR2_GNU_BUILD_SUFFIX="pc-elf" BR2_GNU_TARGET_SUFFIX="nuttx-elf" # BR2_PREFER_IMA is not set # BR2_DEPRECATED is not set diff --git a/misc/buildroot/configs/arm926t-defconfig-nxflat b/misc/buildroot/configs/arm926t-defconfig-nxflat index d449ef4ab..4f6a669c2 100644 --- a/misc/buildroot/configs/arm926t-defconfig-nxflat +++ b/misc/buildroot/configs/arm926t-defconfig-nxflat @@ -59,7 +59,7 @@ BR2_STAGING_DIR="$(BUILD_DIR)/staging_dir" BR2_NUTTX_DIR="$(TOPDIR)/../../nuttx" BR2_TOPDIR_PREFIX="" BR2_TOPDIR_SUFFIX="" -BR2_GNU_BUILD_SUFFIX="arm-elf" +BR2_GNU_BUILD_SUFFIX="pc-elf" BR2_GNU_TARGET_SUFFIX="nuttx-elf" # BR2_PREFER_IMA is not set # BR2_DEPRECATED is not set diff --git a/nuttx/configs/shenzhou/README.txt b/nuttx/configs/shenzhou/README.txt index cad0ad2e7..c04c55ad0 100644 --- a/nuttx/configs/shenzhou/README.txt +++ b/nuttx/configs/shenzhou/README.txt @@ -346,6 +346,9 @@ NuttX buildroot Toolchain cd tools ./configure.sh shenzhou/ + cd .. + make context + 2. Download the latest buildroot package into 3. unpack the buildroot tarball. The resulting directory may @@ -360,9 +363,21 @@ NuttX buildroot Toolchain 7. make - 8. Edit setenv.h, if necessary, so that the PATH variable includes + 8. Edit nuttx/.config to select the buildroot toolchain as described above + and below: + + -CONFIG_STM32_CODESOURCERYW=y + +CONFIG_STM32_BUILDROOT=y + + 9. Edit setenv.h, if necessary, so that the PATH variable includes the path to the newly built binaries. + -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" + +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" + + -#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" + +export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" + See the file configs/README.txt in the buildroot source tree. That has more detailed PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. diff --git a/nuttx/configs/shenzhou/nsh/Make.defs b/nuttx/configs/shenzhou/nsh/Make.defs index 317a95cda..555b0069f 100644 --- a/nuttx/configs/shenzhou/nsh/Make.defs +++ b/nuttx/configs/shenzhou/nsh/Make.defs @@ -84,7 +84,8 @@ ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin CROSSDEV = arm-nuttx-eabi- ARCROSSDEV = arm-nuttx-eabi- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft +# ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/shenzhou/nxwm/Make.defs b/nuttx/configs/shenzhou/nxwm/Make.defs index 96104d6d0..dfb0472a1 100644 --- a/nuttx/configs/shenzhou/nxwm/Make.defs +++ b/nuttx/configs/shenzhou/nxwm/Make.defs @@ -84,7 +84,8 @@ ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin CROSSDEV = arm-nuttx-eabi- ARCROSSDEV = arm-nuttx-eabi- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft +# ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif -- cgit v1.2.3 From a41bc3c2ff6fbf059d715eb8fa0558c3191a346a Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 6 Oct 2012 00:27:17 +0000 Subject: Eliminate a warning git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5216 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/lib/stdio/lib_libvsprintf.c | 8 ++++++++ 1 file changed, 8 insertions(+) (limited to 'nuttx') diff --git a/nuttx/lib/stdio/lib_libvsprintf.c b/nuttx/lib/stdio/lib_libvsprintf.c index 2bf095880..30c988599 100644 --- a/nuttx/lib/stdio/lib_libvsprintf.c +++ b/nuttx/lib/stdio/lib_libvsprintf.c @@ -1169,7 +1169,9 @@ int lib_vsprintf(FAR struct lib_outstream_s *obj, FAR const char *src, va_list a FAR char *ptmp; #ifndef CONFIG_NOPRINTF_FIELDWIDTH int width; +#ifdef CONFIG_LIBC_FLOATINGPOINT int trunc; +#endif uint8_t fmt; #endif uint8_t flags; @@ -1212,7 +1214,9 @@ int lib_vsprintf(FAR struct lib_outstream_s *obj, FAR const char *src, va_list a #ifndef CONFIG_NOPRINTF_FIELDWIDTH fmt = FMT_RJUST; width = 0; +#ifdef CONFIG_LIBC_FLOATINGPOINT trunc = 0; +#endif #endif /* Process each format qualifier. */ @@ -1260,8 +1264,10 @@ int lib_vsprintf(FAR struct lib_outstream_s *obj, FAR const char *src, va_list a int value = va_arg(ap, int); if (IS_HASDOT(flags)) { +#ifdef CONFIG_LIBC_FLOATINGPOINT trunc = value; SET_HASASTERISKTRUNC(flags); +#endif } else { @@ -1300,7 +1306,9 @@ int lib_vsprintf(FAR struct lib_outstream_s *obj, FAR const char *src, va_list a if (IS_HASDOT(flags)) { +#ifdef CONFIG_LIBC_FLOATINGPOINT trunc = n; +#endif } else { -- cgit v1.2.3 From 4d23437df02e0974cb0fbf6d80fe9039037947bd Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 6 Oct 2012 14:50:37 +0000 Subject: Several bugfixes, mostly from Darcy Gong git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5217 42af7a65-404d-4744-a932-0658087f49c3 --- apps/ChangeLog.txt | 4 + apps/netutils/webclient/webclient.c | 14 +-- apps/netutils/webserver/httpd.c | 2 +- nuttx/arch/arm/src/stm32/stm32_eth.c | 1 + nuttx/drivers/mtd/ramtron.c | 220 ++++++++++++++++++----------------- 5 files changed, 129 insertions(+), 112 deletions(-) (limited to 'nuttx') diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index bf2a85a9b..7375adccf 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -364,3 +364,7 @@ There are still a LOT of empty, stub Kconfig files. * Kconfig: Fleshed out apps/examples/buttons/Kconfig. There are still a LOT of empty, stub Kconfig files. + * apps/netutils/webserver/httpd.c: Fix a bug that I introduced in + recent check-ins (Darcy Gong). + * apps/netutils/webclient/webclient.c: Fix another but that I introduced + when I was trying to add correct handling for loss of connection (Darcy Gong) diff --git a/apps/netutils/webclient/webclient.c b/apps/netutils/webclient/webclient.c index 05a63ba38..5a84c4fd1 100644 --- a/apps/netutils/webclient/webclient.c +++ b/apps/netutils/webclient/webclient.c @@ -110,7 +110,7 @@ struct wget_s FAR char *buffer; /* user-provided buffer */ int buflen; /* Length of the user provided buffer */ int offset; /* Offset to the beginning of interesting data */ - int datend; /* Offset+1 to the last valid byte of data in the buffer */ + int datend; /* Offset+1 to the last valid byte of data in the buffer */ /* Buffer HTTP header data and parse line at a time */ @@ -204,7 +204,7 @@ static inline int wget_resolvehost(const char *hostname, in_addr_t *ipaddr) /* 'host' does not point to a valid address string. Try to resolve * the host name to an IP address. */ - + if (resolv_query(hostname, &addr) < 0) { /* Needs to set the errno here */ @@ -401,10 +401,10 @@ exit: * * Returned Value: * 0: if the GET operation completed successfully; - * -1: On a failure with errno set appropriately + * -1: On a failure with errno set appropriately * ****************************************************************************/ - + int wget(FAR const char *url, FAR char *buffer, int buflen, wget_callback_t callback, FAR void *arg) { @@ -524,10 +524,10 @@ int wget(FAR const char *url, FAR char *buffer, int buflen, ret = ws.datend; goto errout_with_errno; } - else if (ret == 0) + else if (ws.datend == 0) { nvdbg("Connection lost\n"); - close(sockfd); + close(sockfd); break; } @@ -567,7 +567,7 @@ int wget(FAR const char *url, FAR char *buffer, int buflen, else { redirected = true; - close(sockfd); + close(sockfd); break; } } diff --git a/apps/netutils/webserver/httpd.c b/apps/netutils/webserver/httpd.c index f96fc5a6c..9f621d67c 100644 --- a/apps/netutils/webserver/httpd.c +++ b/apps/netutils/webserver/httpd.c @@ -694,7 +694,7 @@ static inline int httpd_parse(struct httpd_state *pstate) while (state != STATE_BODY); #if !defined(CONFIG_NETUTILS_HTTPD_SENDFILE) && !defined(CONFIG_NETUTILS_HTTPD_MMAP) - if (0 == strcmp(pstate->ht_filename, "/") + if (0 == strcmp(pstate->ht_filename, "/")) { strncpy(pstate->ht_filename, "/" CONFIG_NETUTILS_HTTPD_INDEX, strlen("/" CONFIG_NETUTILS_HTTPD_INDEX)); } diff --git a/nuttx/arch/arm/src/stm32/stm32_eth.c b/nuttx/arch/arm/src/stm32/stm32_eth.c index 13f02679f..3054142ce 100644 --- a/nuttx/arch/arm/src/stm32/stm32_eth.c +++ b/nuttx/arch/arm/src/stm32/stm32_eth.c @@ -1656,6 +1656,7 @@ static void stm32_receive(FAR struct stm32_ethmac_s *priv) stm32_freebuffer(priv, dev->d_buf); dev->d_buf = NULL; + dev->d_len = 0; } } } diff --git a/nuttx/drivers/mtd/ramtron.c b/nuttx/drivers/mtd/ramtron.c index 074545e2d..34273bccf 100644 --- a/nuttx/drivers/mtd/ramtron.c +++ b/nuttx/drivers/mtd/ramtron.c @@ -98,7 +98,7 @@ #define RAMTRON_WRITE 0x02 /* 1 Write A 0 1-256 */ #define RAMTRON_SLEEP 0xb9 // TODO: #define RAMTRON_RDID 0x9f /* 1 Read Identification 0 0 1-3 */ -#define RAMTRON_SN 0xc3 // TODO: +#define RAMTRON_SN 0xc3 // TODO: /* Status register bit definitions */ @@ -125,12 +125,12 @@ struct ramtron_parts_s { - const char *name; - uint8_t id1; - uint8_t id2; - uint32_t size; - uint8_t addr_len; - uint32_t speed; + const char *name; + uint8_t id1; + uint8_t id2; + uint32_t size; + uint8_t addr_len; + uint32_t speed; }; /* This type represents the state of the MTD device. The struct mtd_dev_s @@ -146,84 +146,86 @@ struct ramtron_dev_s uint8_t pageshift; uint16_t nsectors; uint32_t npages; - const struct ramtron_parts_s *part; /* part instance */ + const struct ramtron_parts_s *part; /* part instance */ }; /************************************************************************************ * Supported Part Lists ************************************************************************************/ -// Defines the initial speed compatible with all devices. In case of RAMTRON -// the defined devices within the part list have all the same speed. -#define RAMTRON_INIT_CLK_MAX 40000000UL +/* Defines the initial speed compatible with all devices. In case of RAMTRON + * the defined devices within the part list have all the same speed. + */ + +#define RAMTRON_INIT_CLK_MAX 40000000UL static struct ramtron_parts_s ramtron_parts[] = { - { - "FM25V02", /* name */ - 0x22, /* id1 */ - 0x00, /* id2 */ - 32L*1024L, /* size */ - 2, /* addr_len */ - 40000000 /* speed */ - }, - { - "FM25VN02", /* name */ - 0x22, /* id1 */ - 0x01, /* id2 */ - 32L*1024L, /* size */ - 2, /* addr_len */ - 40000000 /* speed */ - }, - { - "FM25V05", /* name */ - 0x23, /* id1 */ - 0x00, /* id2 */ - 64L*1024L, /* size */ - 2, /* addr_len */ - 40000000 /* speed */ - }, - { - "FM25VN05", /* name */ - 0x23, /* id1 */ - 0x01, /* id2 */ - 64L*1024L, /* size */ - 2, /* addr_len */ - 40000000 /* speed */ - }, - { - "FM25V10", /* name */ - 0x24, /* id1 */ - 0x00, /* id2 */ - 128L*1024L, /* size */ - 3, /* addr_len */ - 40000000 /* speed */ - }, - { - "FM25VN10", /* name */ - 0x24, /* id1 */ - 0x01, /* id2 */ - 128L*1024L, /* size */ - 3, /* addr_len */ - 40000000 /* speed */ - }, + { + "FM25V02", /* name */ + 0x22, /* id1 */ + 0x00, /* id2 */ + 32L*1024L, /* size */ + 2, /* addr_len */ + 40000000 /* speed */ + }, + { + "FM25VN02", /* name */ + 0x22, /* id1 */ + 0x01, /* id2 */ + 32L*1024L, /* size */ + 2, /* addr_len */ + 40000000 /* speed */ + }, + { + "FM25V05", /* name */ + 0x23, /* id1 */ + 0x00, /* id2 */ + 64L*1024L, /* size */ + 2, /* addr_len */ + 40000000 /* speed */ + }, + { + "FM25VN05", /* name */ + 0x23, /* id1 */ + 0x01, /* id2 */ + 64L*1024L, /* size */ + 2, /* addr_len */ + 40000000 /* speed */ + }, + { + "FM25V10", /* name */ + 0x24, /* id1 */ + 0x00, /* id2 */ + 128L*1024L, /* size */ + 3, /* addr_len */ + 40000000 /* speed */ + }, + { + "FM25VN10", /* name */ + 0x24, /* id1 */ + 0x01, /* id2 */ + 128L*1024L, /* size */ + 3, /* addr_len */ + 40000000 /* speed */ + }, #ifdef CONFIG_RAMTRON_FRAM_NON_JEDEC - { - "FM25H20", /* name */ - 0xff, /* id1 */ - 0xff, /* id2 */ - 256L*1024L, /* size */ - 3, /* addr_len */ - 40000000 /* speed */ - }, - { - NULL, /* name */ - 0, /* id1 */ - 0, /* id2 */ - 0, /* size */ - 0, /* addr_len */ - 0 /* speed */ - } + { + "FM25H20", /* name */ + 0xff, /* id1 */ + 0xff, /* id2 */ + 256L*1024L, /* size */ + 3, /* addr_len */ + 40000000 /* speed */ + }, + { + NULL, /* name */ + 0, /* id1 */ + 0, /* id2 */ + 0, /* size */ + 0, /* addr_len */ + 0 /* speed */ + } #endif }; @@ -240,17 +242,17 @@ static inline int ramtron_readid(struct ramtron_dev_s *priv); static void ramtron_waitwritecomplete(struct ramtron_dev_s *priv); static void ramtron_writeenable(struct ramtron_dev_s *priv); static inline void ramtron_pagewrite(struct ramtron_dev_s *priv, FAR const uint8_t *buffer, - off_t offset); + off_t offset); /* MTD driver methods */ static int ramtron_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks); static ssize_t ramtron_bread(FAR struct mtd_dev_s *dev, off_t startblock, - size_t nblocks, FAR uint8_t *buf); + size_t nblocks, FAR uint8_t *buf); static ssize_t ramtron_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, - size_t nblocks, FAR const uint8_t *buf); + size_t nblocks, FAR const uint8_t *buf); static ssize_t ramtron_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes, - FAR uint8_t *buffer); + FAR uint8_t *buffer); static int ramtron_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg); /************************************************************************************ @@ -317,31 +319,37 @@ static inline int ramtron_readid(struct ramtron_dev_s *priv) /* Send the "Read ID (RDID)" command and read the first three ID bytes */ (void)SPI_SEND(priv->dev, RAMTRON_RDID); - for (i=0; i<6; i++) manufacturer = SPI_SEND(priv->dev, RAMTRON_DUMMY); - memory = SPI_SEND(priv->dev, RAMTRON_DUMMY); - capacity = SPI_SEND(priv->dev, RAMTRON_DUMMY); // fram.id1 - part = SPI_SEND(priv->dev, RAMTRON_DUMMY); // fram.id2 + for (i = 0; i < 6; i++) + { + manufacturer = SPI_SEND(priv->dev, RAMTRON_DUMMY); + } + + memory = SPI_SEND(priv->dev, RAMTRON_DUMMY); + capacity = SPI_SEND(priv->dev, RAMTRON_DUMMY); // fram.id1 + part = SPI_SEND(priv->dev, RAMTRON_DUMMY); // fram.id2 /* Deselect the FLASH and unlock the bus */ SPI_SELECT(priv->dev, SPIDEV_FLASH, false); ramtron_unlock(priv->dev); - // Select part from the part list + /* Select part from the part list */ + for (priv->part = ramtron_parts; - priv->part->name != NULL && !(priv->part->id1 == capacity && priv->part->id2 == part); - priv->part++); - - if (priv->part->name) { - fvdbg("RAMTRON %s of size %d bytes (mf:%02x mem:%02x cap:%02x part:%02x)\n", - priv->part->name, priv->part->size, manufacturer, memory, capacity, part); - - priv->sectorshift = RAMTRON_EMULATE_SECTOR_SHIFT; - priv->nsectors = priv->part->size / (1 << RAMTRON_EMULATE_SECTOR_SHIFT); - priv->pageshift = RAMTRON_EMULATE_PAGE_SHIFT; - priv->npages = priv->part->size / (1 << RAMTRON_EMULATE_PAGE_SHIFT); - return OK; - } + priv->part->name != NULL && !(priv->part->id1 == capacity && priv->part->id2 == part); + priv->part++); + + if (priv->part->name) + { + fvdbg("RAMTRON %s of size %d bytes (mf:%02x mem:%02x cap:%02x part:%02x)\n", + priv->part->name, priv->part->size, manufacturer, memory, capacity, part); + + priv->sectorshift = RAMTRON_EMULATE_SECTOR_SHIFT; + priv->nsectors = priv->part->size / (1 << RAMTRON_EMULATE_SECTOR_SHIFT); + priv->pageshift = RAMTRON_EMULATE_PAGE_SHIFT; + priv->npages = priv->part->size / (1 << RAMTRON_EMULATE_PAGE_SHIFT); + return OK; + } fvdbg("RAMTRON device not found\n"); return -ENODEV; @@ -408,8 +416,10 @@ static inline void ramtron_sendaddr(const struct ramtron_dev_s *priv, uint32_t a DEBUGASSERT(priv->part->addr_len == 3 || priv->part->addr_len == 2); if (priv->part->addr_len == 3) - (void)SPI_SEND(priv->dev, (addr >> 16) & 0xff); - + { + (void)SPI_SEND(priv->dev, (addr >> 16) & 0xff); + } + (void)SPI_SEND(priv->dev, (addr >> 8) & 0xff); (void)SPI_SEND(priv->dev, addr & 0xff); } @@ -419,7 +429,7 @@ static inline void ramtron_sendaddr(const struct ramtron_dev_s *priv, uint32_t a ************************************************************************************/ static inline void ramtron_pagewrite(struct ramtron_dev_s *priv, FAR const uint8_t *buffer, - off_t page) + off_t page) { off_t offset = page << priv->pageshift; @@ -475,7 +485,7 @@ static int ramtron_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nbl ************************************************************************************/ static ssize_t ramtron_bread(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks, - FAR uint8_t *buffer) + FAR uint8_t *buffer) { FAR struct ramtron_dev_s *priv = (FAR struct ramtron_dev_s *)dev; ssize_t nbytes; @@ -489,6 +499,7 @@ static ssize_t ramtron_bread(FAR struct mtd_dev_s *dev, off_t startblock, size_t { return nbytes >> priv->pageshift; } + return (int)nbytes; } @@ -497,7 +508,7 @@ static ssize_t ramtron_bread(FAR struct mtd_dev_s *dev, off_t startblock, size_t ************************************************************************************/ static ssize_t ramtron_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks, - FAR const uint8_t *buffer) + FAR const uint8_t *buffer) { FAR struct ramtron_dev_s *priv = (FAR struct ramtron_dev_s *)dev; size_t blocksleft = nblocks; @@ -512,8 +523,8 @@ static ssize_t ramtron_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_ ramtron_pagewrite(priv, buffer, startblock); startblock++; } - ramtron_unlock(priv->dev); + ramtron_unlock(priv->dev); return nblocks; } @@ -522,7 +533,7 @@ static ssize_t ramtron_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_ ************************************************************************************/ static ssize_t ramtron_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes, - FAR uint8_t *buffer) + FAR uint8_t *buffer) { FAR struct ramtron_dev_s *priv = (FAR struct ramtron_dev_s *)dev; @@ -662,6 +673,7 @@ FAR struct mtd_dev_s *ramtron_initialize(FAR struct spi_dev_s *dev) if (ramtron_readid(priv) != OK) { /* Unrecognized! Discard all of that work we just did and return NULL */ + kfree(priv); priv = NULL; } -- cgit v1.2.3 From 79e092e3627aeaaa351fbbc2c19f3b0311dc4001 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 6 Oct 2012 17:29:36 +0000 Subject: Update all config README.txt files to show that they use the EABI buildroot toolchain git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5218 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/configs/ea3131/README.txt | 182 ++++++------- nuttx/configs/ea3152/README.txt | 192 +++++++------- nuttx/configs/eagle100/README.txt | 236 ++++++++++------- nuttx/configs/ekk-lm3s9b96/README.txt | 61 ++++- nuttx/configs/fire-stm32v2/README.txt | 62 ++++- nuttx/configs/hymini-stm32v/README.txt | 390 ++++++++++++++++------------ nuttx/configs/kwikstik-k40/README.txt | 195 +++++++++----- nuttx/configs/lincoln60/README.txt | 320 +++++++++++++---------- nuttx/configs/lm3s6432-s2e/README.txt | 253 ++++++++++-------- nuttx/configs/lm3s6965-ek/README.txt | 236 ++++++++++------- nuttx/configs/lm3s8962-ek/README.txt | 236 ++++++++++------- nuttx/configs/lpc4330-xplorer/README.txt | 62 ++++- nuttx/configs/lpcxpresso-lpc1768/README.txt | 29 ++- nuttx/configs/mbed/README.txt | 320 +++++++++++++---------- nuttx/configs/mcu123-lpc214x/README.txt | 2 +- nuttx/configs/nucleus2g/README.txt | 320 +++++++++++++---------- nuttx/configs/olimex-lpc1766stk/README.txt | 324 +++++++++++++---------- nuttx/configs/sam3u-ek/README.txt | 250 +++++++++++------- nuttx/configs/stm3210e-eval/README.txt | 62 ++++- nuttx/configs/stm3220g-eval/README.txt | 62 ++++- nuttx/configs/stm3240g-eval/README.txt | 62 ++++- nuttx/configs/stm32f4discovery/README.txt | 62 ++++- nuttx/configs/twr-k60n512/README.txt | 219 ++++++++++------ nuttx/configs/vsn/README.txt | 151 +++++++---- 24 files changed, 2662 insertions(+), 1626 deletions(-) (limited to 'nuttx') diff --git a/nuttx/configs/ea3131/README.txt b/nuttx/configs/ea3131/README.txt index a99011ec5..4d01a4162 100644 --- a/nuttx/configs/ea3131/README.txt +++ b/nuttx/configs/ea3131/README.txt @@ -46,7 +46,7 @@ GNU Toolchain Options CONFIG_LPC31_CODESOURCERYW=y : CodeSourcery under Windows 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_LPC31_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default) 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. @@ -196,12 +196,12 @@ Image Format Then, to build the NuttX binary ready to load with the bootloader, just following these steps: - - cd tools/ # Configure Nuttx - - ./configure.sh ea3131/ostest # (using the ostest configuration for this example) - - cd .. # Set up environment - - . ./setenv.sh # (see notes below) - - make # Make NuttX. This will produce nuttx.bin - - mklpc.sh # Make the bootloader binary (nuttx.lpc) + - cd tools/ # Configure Nuttx + - ./configure.sh ea3131/ostest # (using the ostest configuration for this example) + - cd .. # Set up environment + - . ./setenv.sh # (see notes below) + - make # Make NuttX. This will produce nuttx.bin + - mklpc.sh # Make the bootloader binary (nuttx.lpc) NOTES: @@ -469,121 +469,121 @@ On-Demand Paging ARM/EA3131-specific Configuration Options ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - CONFIG_ARCH - Identifies the arch/ subdirectory. This should - be set to: + CONFIG_ARCH - Identifies the arch/ subdirectory. This should + be set to: - CONFIG_ARCH=arm + CONFIG_ARCH=arm - CONFIG_ARCH_family - For use in C code: + CONFIG_ARCH_family - For use in C code: - CONFIG_ARCH_ARM=y + CONFIG_ARCH_ARM=y - CONFIG_ARCH_architecture - For use in C code: + CONFIG_ARCH_architecture - For use in C code: - CONFIG_ARCH_ARM926EJS=y + CONFIG_ARCH_ARM926EJS=y - CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory + CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory - CONFIG_ARCH_CHIP=lpc313x + CONFIG_ARCH_CHIP=lpc313x - CONFIG_ARCH_CHIP_name - For use in C code + CONFIG_ARCH_CHIP_name - For use in C code - CONFIG_ARCH_CHIP_LPC3131 + CONFIG_ARCH_CHIP_LPC3131 - CONFIG_ARCH_BOARD - Identifies the configs subdirectory and - hence, the board that supports the particular chip or SoC. + CONFIG_ARCH_BOARD - Identifies the configs subdirectory and + hence, the board that supports the particular chip or SoC. - CONFIG_ARCH_BOARD=ea3131 + CONFIG_ARCH_BOARD=ea3131 - CONFIG_ARCH_BOARD_name - For use in C code + CONFIG_ARCH_BOARD_name - For use in C code - CONFIG_ARCH_BOARD_EA3131 + CONFIG_ARCH_BOARD_EA3131 - CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation - of delay loops + CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation + of delay loops - CONFIG_ENDIAN_BIG - define if big endian (default is little - endian) + CONFIG_ENDIAN_BIG - define if big endian (default is little + endian) - CONFIG_DRAM_SIZE - For most ARM9 architectures, this describes the - size of installed DRAM. For the LPC313X, it is used only to - deterimine how to map the executable regions. It is SDRAM size - only if you are executing out of the external SDRAM; or it could - be NOR FLASH size, external SRAM size, or internal SRAM size. + CONFIG_DRAM_SIZE - For most ARM9 architectures, this describes the + size of installed DRAM. For the LPC313X, it is used only to + deterimine how to map the executable regions. It is SDRAM size + only if you are executing out of the external SDRAM; or it could + be NOR FLASH size, external SRAM size, or internal SRAM size. - CONFIG_DRAM_START - The start address of installed DRAM (physical) + CONFIG_DRAM_START - The start address of installed DRAM (physical) - CONFIG_DRAM_VSTART - The startaddress of DRAM (virtual) + CONFIG_DRAM_VSTART - The startaddress of DRAM (virtual) - CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that - have LEDs + CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that + have LEDs - CONFIG_ARCH_IRQPRIO - The LPC313x supports interrupt prioritization + CONFIG_ARCH_IRQPRIO - The LPC313x supports interrupt prioritization - CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt - stack. If defined, this symbol is the size of the interrupt - stack in bytes. If not defined, the user task stacks will be - used during interrupt handling. + CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt + stack. If defined, this symbol is the size of the interrupt + stack in bytes. If not defined, the user task stacks will be + used during interrupt handling. - CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions + CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions - CONFIG_ARCH_BOOTLOADER - Set if you are using a bootloader. + CONFIG_ARCH_BOOTLOADER - Set if you are using a bootloader. - CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. + CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. - CONFIG_ARCH_BUTTONS - Enable support for buttons. Unique to board architecture. + CONFIG_ARCH_BUTTONS - Enable support for buttons. Unique to board architecture. - CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that - cause a 100 second delay during boot-up. This 100 second delay - serves no purpose other than it allows you to calibratre - CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure - the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until - the delay actually is 100 seconds. - CONFIG_ARCH_DMA - Support DMA initialization - CONFIG_ARCH_LOWVECTORS - define if vectors reside at address 0x0000:00000 - Undefine if vectors reside at address 0xffff:0000 - CONFIG_ARCH_ROMPGTABLE - A pre-initialized, read-only page table is available. - If defined, then board-specific logic must also define PGTABLE_BASE_PADDR, - PGTABLE_BASE_VADDR, and all memory section mapping in a file named - board_memorymap.h. + CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that + cause a 100 second delay during boot-up. This 100 second delay + serves no purpose other than it allows you to calibratre + CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure + the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until + the delay actually is 100 seconds. + CONFIG_ARCH_DMA - Support DMA initialization + CONFIG_ARCH_LOWVECTORS - define if vectors reside at address 0x0000:00000 + Undefine if vectors reside at address 0xffff:0000 + CONFIG_ARCH_ROMPGTABLE - A pre-initialized, read-only page table is available. + If defined, then board-specific logic must also define PGTABLE_BASE_PADDR, + PGTABLE_BASE_VADDR, and all memory section mapping in a file named + board_memorymap.h. Individual subsystems can be enabled: - CONFIG_LPC31_MCI, CONFIG_LPC31_SPI, CONFIG_LPC31_UART + CONFIG_LPC31_MCI, CONFIG_LPC31_SPI, CONFIG_LPC31_UART External memory available on the board (see also CONFIG_MM_REGIONS) - CONFIG_LPC31_EXTSRAM0 - Select if external SRAM0 is present - CONFIG_LPC31_EXTSRAM0HEAP - Select if external SRAM0 should be - configured as part of the NuttX heap. - CONFIG_LPC31_EXTSRAM0SIZE - Size (in bytes) of the installed - external SRAM0 memory - CONFIG_LPC31_EXTSRAM1 - Select if external SRAM1 is present - CONFIG_LPC31_EXTSRAM1HEAP - Select if external SRAM1 should be - configured as part of the NuttX heap. - CONFIG_LPC31_EXTSRAM1SIZE - Size (in bytes) of the installed - external SRAM1 memory - CONFIG_LPC31_EXTSDRAM - Select if external SDRAM is present - CONFIG_LPC31_EXTSDRAMHEAP - Select if external SDRAM should be - configured as part of the NuttX heap. - CONFIG_LPC31_EXTSDRAMSIZE - Size (in bytes) of the installed - external SDRAM memory - CONFIG_LPC31_EXTNAND - Select if external NAND is present - CONFIG_LPC31_EXTSDRAMSIZE - Size (in bytes) of the installed - external NAND memory + CONFIG_LPC31_EXTSRAM0 - Select if external SRAM0 is present + CONFIG_LPC31_EXTSRAM0HEAP - Select if external SRAM0 should be + configured as part of the NuttX heap. + CONFIG_LPC31_EXTSRAM0SIZE - Size (in bytes) of the installed + external SRAM0 memory + CONFIG_LPC31_EXTSRAM1 - Select if external SRAM1 is present + CONFIG_LPC31_EXTSRAM1HEAP - Select if external SRAM1 should be + configured as part of the NuttX heap. + CONFIG_LPC31_EXTSRAM1SIZE - Size (in bytes) of the installed + external SRAM1 memory + CONFIG_LPC31_EXTSDRAM - Select if external SDRAM is present + CONFIG_LPC31_EXTSDRAMHEAP - Select if external SDRAM should be + configured as part of the NuttX heap. + CONFIG_LPC31_EXTSDRAMSIZE - Size (in bytes) of the installed + external SDRAM memory + CONFIG_LPC31_EXTNAND - Select if external NAND is present + CONFIG_LPC31_EXTSDRAMSIZE - Size (in bytes) of the installed + external NAND memory LPC313X specific device driver settings - CONFIG_UART_SERIAL_CONSOLE - selects the UART for the - console and ttys0 - CONFIG_UART_RXBUFSIZE - Characters are buffered as received. - This specific the size of the receive buffer - CONFIG_UART_TXBUFSIZE - Characters are buffered before - being sent. This specific the size of the transmit buffer - CONFIG_UART_BAUD - The configure BAUD of the UART. Must be - CONFIG_UART_BITS - The number of bits. Must be either 7 or 8. - CONFIG_UART_PARTIY - 0=no parity, 1=odd parity, 2=even parity - CONFIG_UART_2STOP - Two stop bits + CONFIG_UART_SERIAL_CONSOLE - selects the UART for the + console and ttys0 + CONFIG_UART_RXBUFSIZE - Characters are buffered as received. + This specific the size of the receive buffer + CONFIG_UART_TXBUFSIZE - Characters are buffered before + being sent. This specific the size of the transmit buffer + CONFIG_UART_BAUD - The configure BAUD of the UART. Must be + CONFIG_UART_BITS - The number of bits. Must be either 7 or 8. + CONFIG_UART_PARTIY - 0=no parity, 1=odd parity, 2=even parity + CONFIG_UART_2STOP - Two stop bits Configurations ^^^^^^^^^^^^^^ @@ -591,10 +591,10 @@ Configurations Each EA3131 configuration is maintained in a sudirectory and can be selected as follow: - cd tools - ./configure.sh ea3131/ - cd - - . ./setenv.sh + cd tools + ./configure.sh ea3131/ + cd - + . ./setenv.sh Where is one of the following: diff --git a/nuttx/configs/ea3152/README.txt b/nuttx/configs/ea3152/README.txt index 5b6eb17a9..5b513a620 100644 --- a/nuttx/configs/ea3152/README.txt +++ b/nuttx/configs/ea3152/README.txt @@ -45,7 +45,7 @@ GNU Toolchain Options CONFIG_LPC31_CODESOURCERYW=y : CodeSourcery under Windows 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_LPC31_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default) 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. @@ -165,7 +165,7 @@ NuttX buildroot Toolchain Boot Sequence ^^^^^^^^^^^^^ - LPC313x has on chip bootrom which loads properly formatted images from multiple + LPC315x has on chip bootrom which loads properly formatted images from multiple sources into SRAM. These sources include including SPI Flash, NOR Flash, UART, USB, SD Card, and NAND Flash. @@ -195,12 +195,12 @@ Image Format Then, to build the NuttX binary ready to load with the bootloader, just following these steps: - - cd tools/ # Configure Nuttx - - ./configure.sh ea3152/ostest # (using the ostest configuration for this example) - - cd .. # Set up environment - - . ./setenv.sh # (see notes below) - - make # Make NuttX. This will produce nuttx.bin - - mklpc.sh # Make the bootloader binary (nuttx.lpc) + - cd tools/ # Configure Nuttx + - ./configure.sh ea3152/ostest # (using the ostest configuration for this example) + - cd .. # Set up environment + - . ./setenv.sh # (see notes below) + - make # Make NuttX. This will produce nuttx.bin + - mklpc.sh # Make the bootloader binary (nuttx.lpc) NOTES: @@ -238,7 +238,7 @@ are the steps that I use for loading new code into the EA3152: That will load the NuttX binary into ISRAM and attempt to execute it. -*See the LPC313x documentation if you do not have the FTDI driver installed. +*See the LPC315x documentation if you do not have the FTDI driver installed. Using OpenOCD and GDB ^^^^^^^^^^^^^^^^^^^^^ @@ -275,121 +275,121 @@ Using OpenOCD and GDB ARM/EA3152-specific Configuration Options ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - CONFIG_ARCH - Identifies the arch/ subdirectory. This should - be set to: + CONFIG_ARCH - Identifies the arch/ subdirectory. This should + be set to: - CONFIG_ARCH=arm + CONFIG_ARCH=arm - CONFIG_ARCH_family - For use in C code: + CONFIG_ARCH_family - For use in C code: - CONFIG_ARCH_ARM=y + CONFIG_ARCH_ARM=y - CONFIG_ARCH_architecture - For use in C code: + CONFIG_ARCH_architecture - For use in C code: - CONFIG_ARCH_ARM926EJS=y + CONFIG_ARCH_ARM926EJS=y - CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory + CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory - CONFIG_ARCH_CHIP=lpc313x + CONFIG_ARCH_CHIP=lpc31xx - CONFIG_ARCH_CHIP_name - For use in C code + CONFIG_ARCH_CHIP_name - For use in C code - CONFIG_ARCH_CHIP_LPC3152 + CONFIG_ARCH_CHIP_LPC3152 - CONFIG_ARCH_BOARD - Identifies the configs subdirectory and - hence, the board that supports the particular chip or SoC. + CONFIG_ARCH_BOARD - Identifies the configs subdirectory and + hence, the board that supports the particular chip or SoC. - CONFIG_ARCH_BOARD=ea3152 + CONFIG_ARCH_BOARD=ea3152 - CONFIG_ARCH_BOARD_name - For use in C code + CONFIG_ARCH_BOARD_name - For use in C code - CONFIG_ARCH_BOARD_EA3152 + CONFIG_ARCH_BOARD_EA3152 - CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation - of delay loops + CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation + of delay loops - CONFIG_ENDIAN_BIG - define if big endian (default is little - endian) + CONFIG_ENDIAN_BIG - define if big endian (default is little + endian) - CONFIG_DRAM_SIZE - For most ARM9 architectures, this describes the - size of installed DRAM. For the LPC313X, it is used only to - deterimine how to map the executable regions. It is SDRAM size - only if you are executing out of the external SDRAM; or it could - be NOR FLASH size, external SRAM size, or internal SRAM size. + CONFIG_DRAM_SIZE - For most ARM9 architectures, this describes the + size of installed DRAM. For the LPC315X, it is used only to + deterimine how to map the executable regions. It is SDRAM size + only if you are executing out of the external SDRAM; or it could + be NOR FLASH size, external SRAM size, or internal SRAM size. - CONFIG_DRAM_START - The start address of installed DRAM (physical) + CONFIG_DRAM_START - The start address of installed DRAM (physical) - CONFIG_DRAM_VSTART - The startaddress of DRAM (virtual) + CONFIG_DRAM_VSTART - The startaddress of DRAM (virtual) - CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that - have LEDs + CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that + have LEDs - CONFIG_ARCH_IRQPRIO - The LPC313x supports interrupt prioritization + CONFIG_ARCH_IRQPRIO - The LPC315x supports interrupt prioritization - CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt - stack. If defined, this symbol is the size of the interrupt - stack in bytes. If not defined, the user task stacks will be - used during interrupt handling. + CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt + stack. If defined, this symbol is the size of the interrupt + stack in bytes. If not defined, the user task stacks will be + used during interrupt handling. - CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions + CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions - CONFIG_ARCH_BOOTLOADER - Set if you are using a bootloader. + CONFIG_ARCH_BOOTLOADER - Set if you are using a bootloader. - CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. + CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. - CONFIG_ARCH_BUTTONS - Enable support for buttons. Unique to board architecture. + CONFIG_ARCH_BUTTONS - Enable support for buttons. Unique to board architecture. - CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that - cause a 100 second delay during boot-up. This 100 second delay - serves no purpose other than it allows you to calibratre - CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure - the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until - the delay actually is 100 seconds. - CONFIG_ARCH_DMA - Support DMA initialization - CONFIG_ARCH_LOWVECTORS - define if vectors reside at address 0x0000:00000 - Undefine if vectors reside at address 0xffff:0000 - CONFIG_ARCH_ROMPGTABLE - A pre-initialized, read-only page table is available. - If defined, then board-specific logic must also define PGTABLE_BASE_PADDR, - PGTABLE_BASE_VADDR, and all memory section mapping in a file named - board_memorymap.h. + CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that + cause a 100 second delay during boot-up. This 100 second delay + serves no purpose other than it allows you to calibratre + CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure + the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until + the delay actually is 100 seconds. + CONFIG_ARCH_DMA - Support DMA initialization + CONFIG_ARCH_LOWVECTORS - define if vectors reside at address 0x0000:00000 + Undefine if vectors reside at address 0xffff:0000 + CONFIG_ARCH_ROMPGTABLE - A pre-initialized, read-only page table is available. + If defined, then board-specific logic must also define PGTABLE_BASE_PADDR, + PGTABLE_BASE_VADDR, and all memory section mapping in a file named + board_memorymap.h. Individual subsystems can be enabled: - CONFIG_LPC31_MCI, CONFIG_LPC31_SPI, CONFIG_LPC31_UART + CONFIG_LPC31_MCI, CONFIG_LPC31_SPI, CONFIG_LPC31_UART External memory available on the board (see also CONFIG_MM_REGIONS) - CONFIG_LPC31_EXTSRAM0 - Select if external SRAM0 is present - CONFIG_LPC31_EXTSRAM0HEAP - Select if external SRAM0 should be - configured as part of the NuttX heap. - CONFIG_LPC31_EXTSRAM0SIZE - Size (in bytes) of the installed - external SRAM0 memory - CONFIG_LPC31_EXTSRAM1 - Select if external SRAM1 is present - CONFIG_LPC31_EXTSRAM1HEAP - Select if external SRAM1 should be - configured as part of the NuttX heap. - CONFIG_LPC31_EXTSRAM1SIZE - Size (in bytes) of the installed - external SRAM1 memory - CONFIG_LPC31_EXTSDRAM - Select if external SDRAM is present - CONFIG_LPC31_EXTSDRAMHEAP - Select if external SDRAM should be - configured as part of the NuttX heap. - CONFIG_LPC31_EXTSDRAMSIZE - Size (in bytes) of the installed - external SDRAM memory - CONFIG_LPC31_EXTNAND - Select if external NAND is present - CONFIG_LPC31_EXTSDRAMSIZE - Size (in bytes) of the installed - external NAND memory - - LPC313X specific device driver settings - - CONFIG_UART_SERIAL_CONSOLE - selects the UART for the - console and ttys0 - CONFIG_UART_RXBUFSIZE - Characters are buffered as received. - This specific the size of the receive buffer - CONFIG_UART_TXBUFSIZE - Characters are buffered before - being sent. This specific the size of the transmit buffer - CONFIG_UART_BAUD - The configure BAUD of the UART. Must be - CONFIG_UART_BITS - The number of bits. Must be either 7 or 8. - CONFIG_UART_PARTIY - 0=no parity, 1=odd parity, 2=even parity - CONFIG_UART_2STOP - Two stop bits + CONFIG_LPC31_EXTSRAM0 - Select if external SRAM0 is present + CONFIG_LPC31_EXTSRAM0HEAP - Select if external SRAM0 should be + configured as part of the NuttX heap. + CONFIG_LPC31_EXTSRAM0SIZE - Size (in bytes) of the installed + external SRAM0 memory + CONFIG_LPC31_EXTSRAM1 - Select if external SRAM1 is present + CONFIG_LPC31_EXTSRAM1HEAP - Select if external SRAM1 should be + configured as part of the NuttX heap. + CONFIG_LPC31_EXTSRAM1SIZE - Size (in bytes) of the installed + external SRAM1 memory + CONFIG_LPC31_EXTSDRAM - Select if external SDRAM is present + CONFIG_LPC31_EXTSDRAMHEAP - Select if external SDRAM should be + configured as part of the NuttX heap. + CONFIG_LPC31_EXTSDRAMSIZE - Size (in bytes) of the installed + external SDRAM memory + CONFIG_LPC31_EXTNAND - Select if external NAND is present + CONFIG_LPC31_EXTSDRAMSIZE - Size (in bytes) of the installed + external NAND memory + + LPC315X specific device driver settings + + CONFIG_UART_SERIAL_CONSOLE - selects the UART for the + console and ttys0 + CONFIG_UART_RXBUFSIZE - Characters are buffered as received. + This specific the size of the receive buffer + CONFIG_UART_TXBUFSIZE - Characters are buffered before + being sent. This specific the size of the transmit buffer + CONFIG_UART_BAUD - The configure BAUD of the UART. Must be + CONFIG_UART_BITS - The number of bits. Must be either 7 or 8. + CONFIG_UART_PARTIY - 0=no parity, 1=odd parity, 2=even parity + CONFIG_UART_2STOP - Two stop bits Configurations ^^^^^^^^^^^^^^ @@ -397,10 +397,10 @@ Configurations Each EA3152 configuration is maintained in a sudirectory and can be selected as follow: - cd tools - ./configure.sh ea3152/ - cd - - . ./setenv.sh + cd tools + ./configure.sh ea3152/ + cd - + . ./setenv.sh Where is one of the following: diff --git a/nuttx/configs/eagle100/README.txt b/nuttx/configs/eagle100/README.txt index 47c4f89df..105bd5ff1 100644 --- a/nuttx/configs/eagle100/README.txt +++ b/nuttx/configs/eagle100/README.txt @@ -110,8 +110,8 @@ CodeSourcery on Linux For an example of a CodeSourcery-under-Linux Make.defs file, see configs/stm3210e-eval/nsh/Make.defs. -NuttX buildroot Toolchain -^^^^^^^^^^^^^^^^^^^^^^^^^ +NuttX EABI "buildroot" Toolchain +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ A GNU GCC-based toolchain is assumed. The files */setenv.sh should be modified to point to the correct path to the Cortex-M3 GCC toolchain (if @@ -134,7 +134,7 @@ NuttX buildroot Toolchain 4. cd /buildroot - 5. cp configs/cortexm3-defconfig-4.3.3 .config + 5. cp configs/cortexm3-eabi-defconfig-4.6.3 .config 6. make oldconfig @@ -144,9 +144,59 @@ NuttX buildroot Toolchain the path to the newly built binaries. See the file configs/README.txt in the buildroot source tree. That has more - detailed PLUS some special instructions that you will need to follow if you are + details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. +NuttX OABI "buildroot" Toolchain +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + + The older, OABI buildroot toolchain is also available. To use the OABI + toolchain: + + 1. When building the buildroot toolchain, either (1) modify the cortexm3-eabi-defconfig-4.6.3 + configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI + configuration such as cortexm3-defconfig-4.3.3 + + 2. Modify the Make.defs file to use the OABI converntions: + + +CROSSDEV = arm-nuttx-elf- + +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + -CROSSDEV = arm-nuttx-eabi- + -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + +NXFLAT Toolchain +^^^^^^^^^^^^^^^^ + + If you are *not* using the NuttX buildroot toolchain and you want to use + the NXFLAT tools, then you will still have to build a portion of the buildroot + tools -- just the NXFLAT tools. The buildroot with the NXFLAT tools can + be downloaded from the NuttX SourceForge download site + (https://sourceforge.net/projects/nuttx/files/). + + This GNU toolchain builds and executes in the Linux or Cygwin environment. + + 1. You must have already configured Nuttx in /nuttx. + + cd tools + ./configure.sh lpcxpresso-lpc1768/ + + 2. Download the latest buildroot package into + + 3. unpack the buildroot tarball. The resulting directory may + have versioning information on it like buildroot-x.y.z. If so, + rename /buildroot-x.y.z to /buildroot. + + 4. cd /buildroot + + 5. cp configs/cortexm3-defconfig-nxflat .config + + 6. make oldconfig + + 7. make + + 8. Edit setenv.h, if necessary, so that the PATH variable includes + the path to the newly builtNXFLAT binaries. + Ethernet-Bootloader ^^^^^^^^^^^^^^^^^^^ @@ -207,127 +257,127 @@ Ethernet-Bootloader Eagle100-specific Configuration Options ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - CONFIG_ARCH - Identifies the arch/ subdirectory. This should - be set to: + CONFIG_ARCH - Identifies the arch/ subdirectory. This should + be set to: - CONFIG_ARCH=arm + CONFIG_ARCH=arm - CONFIG_ARCH_family - For use in C code: + CONFIG_ARCH_family - For use in C code: - CONFIG_ARCH_ARM=y + CONFIG_ARCH_ARM=y - CONFIG_ARCH_architecture - For use in C code: + CONFIG_ARCH_architecture - For use in C code: - CONFIG_ARCH_CORTEXM3=y + CONFIG_ARCH_CORTEXM3=y - CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory + CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory - CONFIG_ARCH_CHIP=lm3s + CONFIG_ARCH_CHIP=lm3s - CONFIG_ARCH_CHIP_name - For use in C code to identify the exact - chip: + CONFIG_ARCH_CHIP_name - For use in C code to identify the exact + chip: - CONFIG_ARCH_CHIP_LM3S6918 + CONFIG_ARCH_CHIP_LM3S6918 - CONFIG_ARCH_BOARD - Identifies the configs subdirectory and - hence, the board that supports the particular chip or SoC. + CONFIG_ARCH_BOARD - Identifies the configs subdirectory and + hence, the board that supports the particular chip or SoC. - CONFIG_ARCH_BOARD=eagle100 (for the MicroMint Eagle-100 development board) + CONFIG_ARCH_BOARD=eagle100 (for the MicroMint Eagle-100 development board) - CONFIG_ARCH_BOARD_name - For use in C code + CONFIG_ARCH_BOARD_name - For use in C code - CONFIG_ARCH_BOARD_EAGLE100 + CONFIG_ARCH_BOARD_EAGLE100 - CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation - of delay loops + CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation + of delay loops - CONFIG_ENDIAN_BIG - define if big endian (default is little - endian) + CONFIG_ENDIAN_BIG - define if big endian (default is little + endian) - CONFIG_DRAM_SIZE - Describes the installed DRAM (SRAM in this case): + CONFIG_DRAM_SIZE - Describes the installed DRAM (SRAM in this case): - CONFIG_DRAM_SIZE=0x00010000 (64Kb) + CONFIG_DRAM_SIZE=0x00010000 (64Kb) - CONFIG_DRAM_START - The start address of installed DRAM + CONFIG_DRAM_START - The start address of installed DRAM - CONFIG_DRAM_START=0x20000000 + CONFIG_DRAM_START=0x20000000 - CONFIG_ARCH_IRQPRIO - The LM3S6918 supports interrupt prioritization + CONFIG_ARCH_IRQPRIO - The LM3S6918 supports interrupt prioritization - CONFIG_ARCH_IRQPRIO=y + CONFIG_ARCH_IRQPRIO=y - CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that - have LEDs + CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that + have LEDs - CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt - stack. If defined, this symbol is the size of the interrupt - stack in bytes. If not defined, the user task stacks will be - used during interrupt handling. + CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt + stack. If defined, this symbol is the size of the interrupt + stack in bytes. If not defined, the user task stacks will be + used during interrupt handling. - CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions + CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions - CONFIG_ARCH_BOOTLOADER - Configure to use the MicroMint Eagle-100 - Ethernet bootloader. + CONFIG_ARCH_BOOTLOADER - Configure to use the MicroMint Eagle-100 + Ethernet bootloader. - CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. + CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. - CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that - cause a 100 second delay during boot-up. This 100 second delay - serves no purpose other than it allows you to calibratre - CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure - the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until - the delay actually is 100 seconds. + CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that + cause a 100 second delay during boot-up. This 100 second delay + serves no purpose other than it allows you to calibratre + CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure + the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until + the delay actually is 100 seconds. There are configurations for disabling support for interrupts GPIO ports. GPIOH and GPIOJ must be disabled because they do not exist on the LM3S6918. Additional interrupt support can be disabled if desired to reduce memory footprint. - CONFIG_LM3S_DISABLE_GPIOA_IRQS=n - CONFIG_LM3S_DISABLE_GPIOB_IRQS=n - CONFIG_LM3S_DISABLE_GPIOC_IRQS=n - CONFIG_LM3S_DISABLE_GPIOD_IRQS=n - CONFIG_LM3S_DISABLE_GPIOE_IRQS=n - CONFIG_LM3S_DISABLE_GPIOF_IRQS=n - CONFIG_LM3S_DISABLE_GPIOG_IRQS=n - CONFIG_LM3S_DISABLE_GPIOH_IRQS=y - CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y + CONFIG_LM3S_DISABLE_GPIOA_IRQS=n + CONFIG_LM3S_DISABLE_GPIOB_IRQS=n + CONFIG_LM3S_DISABLE_GPIOC_IRQS=n + CONFIG_LM3S_DISABLE_GPIOD_IRQS=n + CONFIG_LM3S_DISABLE_GPIOE_IRQS=n + CONFIG_LM3S_DISABLE_GPIOF_IRQS=n + CONFIG_LM3S_DISABLE_GPIOG_IRQS=n + CONFIG_LM3S_DISABLE_GPIOH_IRQS=y + CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y LM3S6818 specific device driver settings - CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn for the - console and ttys0 (default is the UART0). - CONFIG_UARTn_RXBUFSIZE - Characters are buffered as received. - This specific the size of the receive buffer - CONFIG_UARTn_TXBUFSIZE - Characters are buffered before - being sent. This specific the size of the transmit buffer - CONFIG_UARTn_BAUD - The configure BAUD of the UART. Must be - CONFIG_UARTn_BITS - The number of bits. Must be either 7 or 8. - CONFIG_UARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity - CONFIG_UARTn_2STOP - Two stop bits - - CONFIG_SSI0_DISABLE - Select to disable support for SSI0 - CONFIG_SSI1_DISABLE - Select to disable support for SSI1 - CONFIG_SSI_POLLWAIT - Select to disable interrupt driven SSI support. - Poll-waiting is recommended if the interrupt rate would be to - high in the interrupt driven case. - CONFIG_SSI_TXLIMIT - Write this many words to the Tx FIFO before - emptying the Rx FIFO. If the SPI frequency is high and this - value is large, then larger values of this setting may cause - Rx FIFO overrun errors. Default: half of the Tx FIFO size (4). - - CONFIG_LM3S_ETHERNET - This must be set (along with CONFIG_NET) - to build the LM3S Ethernet driver - CONFIG_LM3S_ETHLEDS - Enable to use Ethernet LEDs on the board. - CONFIG_LM3S_BOARDMAC - If the board-specific logic can provide - a MAC address (via lm3s_ethernetmac()), then this should be selected. - CONFIG_LM3S_ETHHDUPLEX - Set to force half duplex operation - CONFIG_LM3S_ETHNOAUTOCRC - Set to suppress auto-CRC generation - CONFIG_LM3S_ETHNOPAD - Set to suppress Tx padding - CONFIG_LM3S_MULTICAST - Set to enable multicast frames - CONFIG_LM3S_PROMISCUOUS - Set to enable promiscuous mode - CONFIG_LM3S_BADCRC - Set to enable bad CRC rejection. - CONFIG_LM3S_DUMPPACKET - Dump each packet received/sent to the console. + CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn for the + console and ttys0 (default is the UART0). + CONFIG_UARTn_RXBUFSIZE - Characters are buffered as received. + This specific the size of the receive buffer + CONFIG_UARTn_TXBUFSIZE - Characters are buffered before + being sent. This specific the size of the transmit buffer + CONFIG_UARTn_BAUD - The configure BAUD of the UART. Must be + CONFIG_UARTn_BITS - The number of bits. Must be either 7 or 8. + CONFIG_UARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity + CONFIG_UARTn_2STOP - Two stop bits + + CONFIG_SSI0_DISABLE - Select to disable support for SSI0 + CONFIG_SSI1_DISABLE - Select to disable support for SSI1 + CONFIG_SSI_POLLWAIT - Select to disable interrupt driven SSI support. + Poll-waiting is recommended if the interrupt rate would be to + high in the interrupt driven case. + CONFIG_SSI_TXLIMIT - Write this many words to the Tx FIFO before + emptying the Rx FIFO. If the SPI frequency is high and this + value is large, then larger values of this setting may cause + Rx FIFO overrun errors. Default: half of the Tx FIFO size (4). + + CONFIG_LM3S_ETHERNET - This must be set (along with CONFIG_NET) + to build the LM3S Ethernet driver + CONFIG_LM3S_ETHLEDS - Enable to use Ethernet LEDs on the board. + CONFIG_LM3S_BOARDMAC - If the board-specific logic can provide + a MAC address (via lm3s_ethernetmac()), then this should be selected. + CONFIG_LM3S_ETHHDUPLEX - Set to force half duplex operation + CONFIG_LM3S_ETHNOAUTOCRC - Set to suppress auto-CRC generation + CONFIG_LM3S_ETHNOPAD - Set to suppress Tx padding + CONFIG_LM3S_MULTICAST - Set to enable multicast frames + CONFIG_LM3S_PROMISCUOUS - Set to enable promiscuous mode + CONFIG_LM3S_BADCRC - Set to enable bad CRC rejection. + CONFIG_LM3S_DUMPPACKET - Dump each packet received/sent to the console. Configurations ^^^^^^^^^^^^^^ @@ -335,10 +385,10 @@ Configurations Each Eagle-100 configuration is maintained in a sudirectory and can be selected as follow: - cd tools - ./configure.sh eagle100/ - cd - - . ./setenv.sh + cd tools + ./configure.sh eagle100/ + cd - + . ./setenv.sh Where is one of the following: diff --git a/nuttx/configs/ekk-lm3s9b96/README.txt b/nuttx/configs/ekk-lm3s9b96/README.txt index 539eb0c26..16568dbda 100644 --- a/nuttx/configs/ekk-lm3s9b96/README.txt +++ b/nuttx/configs/ekk-lm3s9b96/README.txt @@ -10,7 +10,9 @@ Contents Development Environment GNU Toolchain Options IDEs - NuttX buildroot Toolchain + NuttX EABI "buildroot" Toolchain + NuttX OABI "buildroot" Toolchain + NXFLAT Toolchain Stellaris EKK-LM3S9B96 Evaluation Kit Configuration Options Configurations @@ -186,8 +188,8 @@ IDEs Startup files will probably cause you some headaches. The NuttX startup file is arch/arm/src/lm3s/lm3s_vectors.S. -NuttX buildroot Toolchain -^^^^^^^^^^^^^^^^^^^^^^^^^ +NuttX EABI "buildroot" Toolchain +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ A GNU GCC-based toolchain is assumed. The files */setenv.sh should be modified to point to the correct path to the Cortex-M3 GCC toolchain (if @@ -210,7 +212,7 @@ NuttX buildroot Toolchain 4. cd /buildroot - 5. cp configs/cortexm3-defconfig-4.3.3 .config + 5. cp configs/cortexm3-eabi-defconfig-4.6.3 .config 6. make oldconfig @@ -220,11 +222,58 @@ NuttX buildroot Toolchain the path to the newly built binaries. See the file configs/README.txt in the buildroot source tree. That has more - detailed PLUS some special instructions that you will need to follow if you + details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. - NOTE: This is an OABI toolchain. +NuttX OABI "buildroot" Toolchain +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + The older, OABI buildroot toolchain is also available. To use the OABI + toolchain: + + 1. When building the buildroot toolchain, either (1) modify the cortexm3-eabi-defconfig-4.6.3 + configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI + configuration such as cortexm3-defconfig-4.3.3 + + 2. Modify the Make.defs file to use the OABI converntions: + + +CROSSDEV = arm-nuttx-elf- + +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + -CROSSDEV = arm-nuttx-eabi- + -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + +NXFLAT Toolchain +^^^^^^^^^^^^^^^^ + + If you are *not* using the NuttX buildroot toolchain and you want to use + the NXFLAT tools, then you will still have to build a portion of the buildroot + tools -- just the NXFLAT tools. The buildroot with the NXFLAT tools can + be downloaded from the NuttX SourceForge download site + (https://sourceforge.net/projects/nuttx/files/). + + This GNU toolchain builds and executes in the Linux or Cygwin environment. + + 1. You must have already configured Nuttx in /nuttx. + + cd tools + ./configure.sh lpcxpresso-lpc1768/ + + 2. Download the latest buildroot package into + + 3. unpack the buildroot tarball. The resulting directory may + have versioning information on it like buildroot-x.y.z. If so, + rename /buildroot-x.y.z to /buildroot. + + 4. cd /buildroot + + 5. cp configs/cortexm3-defconfig-nxflat .config + + 6. make oldconfig + + 7. make + + 8. Edit setenv.h, if necessary, so that the PATH variable includes + the path to the newly builtNXFLAT binaries. Stellaris EKK-LM3S9B96 Evaluation Kit Configuration Options ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ diff --git a/nuttx/configs/fire-stm32v2/README.txt b/nuttx/configs/fire-stm32v2/README.txt index 6382a7363..74f3c7294 100644 --- a/nuttx/configs/fire-stm32v2/README.txt +++ b/nuttx/configs/fire-stm32v2/README.txt @@ -15,7 +15,9 @@ Contents - Development Environment - GNU Toolchain Options - IDEs - - NuttX buildroot Toolchain + - NuttX EABI "buildroot" Toolchain + - NuttX OABI "buildroot" Toolchain + - NXFLAT Toolchain - DFU and JTAG - OpenOCD - LEDs @@ -308,8 +310,8 @@ IDEs one time from the Cygwin command line in order to obtain the pre-built startup object needed by RIDE. -NuttX buildroot Toolchain -========================= +NuttX EABI "buildroot" Toolchain +================================ A GNU GCC-based toolchain is assumed. The files */setenv.sh should be modified to point to the correct path to the Cortex-M3 GCC toolchain (if @@ -332,7 +334,7 @@ NuttX buildroot Toolchain 4. cd /buildroot - 5. cp configs/cortexm3-defconfig-4.3.3 .config + 5. cp configs/cortexm3-eabi-defconfig-4.6.3 .config 6. make oldconfig @@ -342,9 +344,59 @@ NuttX buildroot Toolchain the path to the newly built binaries. See the file configs/README.txt in the buildroot source tree. That has more - detailed PLUS some special instructions that you will need to follow if you are + details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. +NuttX OABI "buildroot" Toolchain +================================ + + The older, OABI buildroot toolchain is also available. To use the OABI + toolchain: + + 1. When building the buildroot toolchain, either (1) modify the cortexm3-eabi-defconfig-4.6.3 + configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI + configuration such as cortexm3-defconfig-4.3.3 + + 2. Modify the Make.defs file to use the OABI converntions: + + +CROSSDEV = arm-nuttx-elf- + +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + -CROSSDEV = arm-nuttx-eabi- + -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + +NXFLAT Toolchain +================ + + If you are *not* using the NuttX buildroot toolchain and you want to use + the NXFLAT tools, then you will still have to build a portion of the buildroot + tools -- just the NXFLAT tools. The buildroot with the NXFLAT tools can + be downloaded from the NuttX SourceForge download site + (https://sourceforge.net/projects/nuttx/files/). + + This GNU toolchain builds and executes in the Linux or Cygwin environment. + + 1. You must have already configured Nuttx in /nuttx. + + cd tools + ./configure.sh lpcxpresso-lpc1768/ + + 2. Download the latest buildroot package into + + 3. unpack the buildroot tarball. The resulting directory may + have versioning information on it like buildroot-x.y.z. If so, + rename /buildroot-x.y.z to /buildroot. + + 4. cd /buildroot + + 5. cp configs/cortexm3-defconfig-nxflat .config + + 6. make oldconfig + + 7. make + + 8. Edit setenv.h, if necessary, so that the PATH variable includes + the path to the newly builtNXFLAT binaries. + DFU and JTAG ============ diff --git a/nuttx/configs/hymini-stm32v/README.txt b/nuttx/configs/hymini-stm32v/README.txt index 75c67adeb..03658be0a 100644 --- a/nuttx/configs/hymini-stm32v/README.txt +++ b/nuttx/configs/hymini-stm32v/README.txt @@ -10,7 +10,9 @@ Contents - Development Environment - GNU Toolchain Options - IDEs - - NuttX buildroot Toolchain + - NuttX EABI "buildroot" Toolchain + - NuttX OABI "buildroot" Toolchain + - NXFLAT Toolchain - DFU - LEDs - RTC @@ -47,7 +49,7 @@ GNU Toolchain Options CONFIG_STM32_CODESOURCERYL=y : CodeSourcery under Linux 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_STM32_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default) If you are not using CONFIG_STM32_BUILDROOT, then you may also have to modify the PATH in the setenv.h file if your make cannot find the tools. @@ -128,8 +130,8 @@ IDEs one time from the Cygwin command line in order to obtain the pre-built startup object needed by RIDE. -NuttX buildroot Toolchain -========================= +NuttX EABI "buildroot" Toolchain +================================ A GNU GCC-based toolchain is assumed. The files */setenv.sh should be modified to point to the correct path to the Cortex-M3 GCC toolchain (if @@ -152,7 +154,7 @@ NuttX buildroot Toolchain 4. cd /buildroot - 5. cp configs/cortexm3-defconfig-4.3.3 .config + 5. cp configs/cortexm3-eabi-defconfig-4.6.3 .config 6. make oldconfig @@ -162,9 +164,59 @@ NuttX buildroot Toolchain the path to the newly built binaries. See the file configs/README.txt in the buildroot source tree. That has more - detailed PLUS some special instructions that you will need to follow if you are + details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. +NuttX OABI "buildroot" Toolchain +================================ + + The older, OABI buildroot toolchain is also available. To use the OABI + toolchain: + + 1. When building the buildroot toolchain, either (1) modify the cortexm3-eabi-defconfig-4.6.3 + configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI + configuration such as cortexm3-defconfig-4.3.3 + + 2. Modify the Make.defs file to use the OABI converntions: + + +CROSSDEV = arm-nuttx-elf- + +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + -CROSSDEV = arm-nuttx-eabi- + -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + +NXFLAT Toolchain +================ + + If you are *not* using the NuttX buildroot toolchain and you want to use + the NXFLAT tools, then you will still have to build a portion of the buildroot + tools -- just the NXFLAT tools. The buildroot with the NXFLAT tools can + be downloaded from the NuttX SourceForge download site + (https://sourceforge.net/projects/nuttx/files/). + + This GNU toolchain builds and executes in the Linux or Cygwin environment. + + 1. You must have already configured Nuttx in /nuttx. + + cd tools + ./configure.sh lpcxpresso-lpc1768/ + + 2. Download the latest buildroot package into + + 3. unpack the buildroot tarball. The resulting directory may + have versioning information on it like buildroot-x.y.z. If so, + rename /buildroot-x.y.z to /buildroot. + + 4. cd /buildroot + + 5. cp configs/cortexm3-defconfig-nxflat .config + + 6. make oldconfig + + 7. make + + 8. Edit setenv.h, if necessary, so that the PATH variable includes + the path to the newly builtNXFLAT binaries. + DFU === @@ -218,16 +270,16 @@ The HY-MiniSTM32 board provides only two controlable LEDs labeled LED1 and LED2. Usage of these LEDs is defined in include/board.h and src/up_leds.c. They are encoded as follows: - SYMBOL Meaning LED1* LED2 - ------------------- ----------------------- ------- ------- - LED_STARTED NuttX has been started OFF OFF - LED_HEAPALLOCATE Heap has been allocated ON OFF - LED_IRQSENABLED Interrupts enabled OFF ON - LED_STACKCREATED Idle stack created ON OFF - LED_INIRQ In an interrupt** OFF N/C - LED_SIGNAL In a signal handler*** N/C ON - LED_ASSERTION An assertion failed ON ON - LED_PANIC The system has crashed BLINK BLINK + SYMBOL Meaning LED1* LED2 + ------------------- ----------------------- ------- ------- + LED_STARTED NuttX has been started OFF OFF + LED_HEAPALLOCATE Heap has been allocated ON OFF + LED_IRQSENABLED Interrupts enabled OFF ON + LED_STACKCREATED Idle stack created ON OFF + LED_INIRQ In an interrupt** OFF N/C + LED_SIGNAL In a signal handler*** N/C ON + LED_ASSERTION An assertion failed ON ON + LED_PANIC The system has crashed BLINK BLINK LED_IDLE STM32 is is sleep mode (Optional, not used) * If Nuttx starts correctly, normal state is to have LED1 on and LED2 off. @@ -269,123 +321,123 @@ RTC HY-Mini specific Configuration Options ============================================ - CONFIG_ARCH - Identifies the arch/ subdirectory. This should - be set to: + CONFIG_ARCH - Identifies the arch/ subdirectory. This should + be set to: - CONFIG_ARCH=arm + CONFIG_ARCH=arm - CONFIG_ARCH_family - For use in C code: + CONFIG_ARCH_family - For use in C code: - CONFIG_ARCH_ARM=y + CONFIG_ARCH_ARM=y - CONFIG_ARCH_architecture - For use in C code: + CONFIG_ARCH_architecture - For use in C code: - CONFIG_ARCH_CORTEXM3=y + CONFIG_ARCH_CORTEXM3=y - CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory + CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory - CONFIG_ARCH_CHIP=stm32 + CONFIG_ARCH_CHIP=stm32 - CONFIG_ARCH_CHIP_name - For use in C code to identify the exact - chip: + CONFIG_ARCH_CHIP_name - For use in C code to identify the exact + chip: - CONFIG_ARCH_CHIP_STM32F103VCT6 + CONFIG_ARCH_CHIP_STM32F103VCT6 CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG - Enables special STM32 clock configuration features. CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG=n - CONFIG_ARCH_BOARD - Identifies the configs subdirectory and - hence, the board that supports the particular chip or SoC. + CONFIG_ARCH_BOARD - Identifies the configs subdirectory and + hence, the board that supports the particular chip or SoC. - CONFIG_ARCH_BOARD=hymini-stm32v (for the HY-Mini development board) + CONFIG_ARCH_BOARD=hymini-stm32v (for the HY-Mini development board) - CONFIG_ARCH_BOARD_name - For use in C code + CONFIG_ARCH_BOARD_name - For use in C code - CONFIG_ARCH_BOARD_HYMINI_STM32V=y + CONFIG_ARCH_BOARD_HYMINI_STM32V=y - CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation - of delay loops + CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation + of delay loops - CONFIG_ENDIAN_BIG - define if big endian (default is little - endian) + CONFIG_ENDIAN_BIG - define if big endian (default is little + endian) - CONFIG_DRAM_SIZE - Describes the installed DRAM (SRAM in this case): + CONFIG_DRAM_SIZE - Describes the installed DRAM (SRAM in this case): - CONFIG_DRAM_SIZE=0x0000C000 (48Kb) + CONFIG_DRAM_SIZE=0x0000C000 (48Kb) - CONFIG_DRAM_START - The start address of installed DRAM + CONFIG_DRAM_START - The start address of installed DRAM - CONFIG_DRAM_START=0x20000000 + CONFIG_DRAM_START=0x20000000 - CONFIG_ARCH_IRQPRIO - The STM32F103V supports interrupt prioritization + CONFIG_ARCH_IRQPRIO - The STM32F103V supports interrupt prioritization - CONFIG_ARCH_IRQPRIO=y + CONFIG_ARCH_IRQPRIO=y - CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that - have LEDs + CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that + have LEDs - CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt - stack. If defined, this symbol is the size of the interrupt - stack in bytes. If not defined, the user task stacks will be - used during interrupt handling. + CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt + stack. If defined, this symbol is the size of the interrupt + stack in bytes. If not defined, the user task stacks will be + used during interrupt handling. - CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions + CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions - CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. + CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. - CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that - cause a 100 second delay during boot-up. This 100 second delay - serves no purpose other than it allows you to calibratre - CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure - the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until - the delay actually is 100 seconds. + CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that + cause a 100 second delay during boot-up. This 100 second delay + serves no purpose other than it allows you to calibratre + CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure + the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until + the delay actually is 100 seconds. Individual subsystems can be enabled: - AHB - --- - CONFIG_STM32_DMA1 - CONFIG_STM32_DMA2 - CONFIG_STM32_CRC - CONFIG_STM32_FSMC - CONFIG_STM32_SDIO - - APB1 - ---- - CONFIG_STM32_TIM2 - CONFIG_STM32_TIM3 (required for PWM control of LCD backlight) - CONFIG_STM32_TIM4 - CONFIG_STM32_TIM5 - CONFIG_STM32_TIM6 - CONFIG_STM32_TIM7 - CONFIG_STM32_IWDG - CONFIG_STM32_WWDG - CONFIG_STM32_IWDG - CONFIG_STM32_SPI2 - CONFIG_STM32_SPI4 - CONFIG_STM32_USART2 - CONFIG_STM32_USART3 - CONFIG_STM32_UART4 - CONFIG_STM32_UART5 - CONFIG_STM32_I2C1 - CONFIG_STM32_I2C2 - CONFIG_STM32_USB - CONFIG_STM32_CAN1 - CONFIG_STM32_BKP - CONFIG_STM32_PWR - CONFIG_STM32_DAC - CONFIG_STM32_USB - - APB2 - ---- - CONFIG_STM32_ADC1 - CONFIG_STM32_ADC2 - CONFIG_STM32_TIM1 - CONFIG_STM32_SPI1 - CONFIG_STM32_TIM8 - CONFIG_STM32_USART1 - CONFIG_STM32_ADC3 + AHB + --- + CONFIG_STM32_DMA1 + CONFIG_STM32_DMA2 + CONFIG_STM32_CRC + CONFIG_STM32_FSMC + CONFIG_STM32_SDIO + + APB1 + ---- + CONFIG_STM32_TIM2 + CONFIG_STM32_TIM3 (required for PWM control of LCD backlight) + CONFIG_STM32_TIM4 + CONFIG_STM32_TIM5 + CONFIG_STM32_TIM6 + CONFIG_STM32_TIM7 + CONFIG_STM32_IWDG + CONFIG_STM32_WWDG + CONFIG_STM32_IWDG + CONFIG_STM32_SPI2 + CONFIG_STM32_SPI4 + CONFIG_STM32_USART2 + CONFIG_STM32_USART3 + CONFIG_STM32_UART4 + CONFIG_STM32_UART5 + CONFIG_STM32_I2C1 + CONFIG_STM32_I2C2 + CONFIG_STM32_USB + CONFIG_STM32_CAN1 + CONFIG_STM32_BKP + CONFIG_STM32_PWR + CONFIG_STM32_DAC + CONFIG_STM32_USB + + APB2 + ---- + CONFIG_STM32_ADC1 + CONFIG_STM32_ADC2 + CONFIG_STM32_TIM1 + CONFIG_STM32_SPI1 + CONFIG_STM32_TIM8 + CONFIG_STM32_USART1 + CONFIG_STM32_ADC3 Timer and I2C devices may need to the following to force power to be applied unconditionally at power up. (Otherwise, the device is powered when it is @@ -405,84 +457,84 @@ HY-Mini specific Configuration Options to assign the timer (n) for used by the ADC or DAC, but then you also have to configure which ADC or DAC (m) it is assigned to. - CONFIG_STM32_TIMn_PWM Reserve timer n for use by PWM, n=1,..,8 - CONFIG_STM32_TIMn_ADC Reserve timer n for use by ADC, n=1,..,8 - CONFIG_STM32_TIMn_ADCm Reserve timer n to trigger ADCm, n=1,..,8, m=1,..,3 - CONFIG_STM32_TIMn_DAC Reserve timer n for use by DAC, n=1,..,8 - CONFIG_STM32_TIMn_DACm Reserve timer n to trigger DACm, n=1,..,8, m=1,..,2 + CONFIG_STM32_TIMn_PWM Reserve timer n for use by PWM, n=1,..,8 + CONFIG_STM32_TIMn_ADC Reserve timer n for use by ADC, n=1,..,8 + CONFIG_STM32_TIMn_ADCm Reserve timer n to trigger ADCm, n=1,..,8, m=1,..,3 + CONFIG_STM32_TIMn_DAC Reserve timer n for use by DAC, n=1,..,8 + CONFIG_STM32_TIMn_DACm Reserve timer n to trigger DACm, n=1,..,8, m=1,..,2 Others alternate pin mappings available: - CONFIG_STM32_TIM1_FULL_REMAP - CONFIG_STM32_TIM1_PARTIAL_REMAP - CONFIG_STM32_TIM2_FULL_REMAP - CONFIG_STM32_TIM2_PARTIAL_REMAP_1 - CONFIG_STM32_TIM2_PARTIAL_REMAP_2 - CONFIG_STM32_TIM3_FULL_REMAP - CONFIG_STM32_TIM3_PARTIAL_REMAP - CONFIG_STM32_TIM4_REMAP - CONFIG_STM32_USART1_REMAP - CONFIG_STM32_USART2_REMAP - CONFIG_STM32_USART3_FULL_REMAP - CONFIG_STM32_USART3_PARTIAL_REMAP - CONFIG_STM32_SPI1_REMAP - CONFIG_STM32_SPI3_REMAP - CONFIG_STM32_I2C1_REMAP - CONFIG_STM32_CAN1_REMAP1 - CONFIG_STM32_CAN1_REMAP2 - CONFIG_STM32_CAN2_REMAP + CONFIG_STM32_TIM1_FULL_REMAP + CONFIG_STM32_TIM1_PARTIAL_REMAP + CONFIG_STM32_TIM2_FULL_REMAP + CONFIG_STM32_TIM2_PARTIAL_REMAP_1 + CONFIG_STM32_TIM2_PARTIAL_REMAP_2 + CONFIG_STM32_TIM3_FULL_REMAP + CONFIG_STM32_TIM3_PARTIAL_REMAP + CONFIG_STM32_TIM4_REMAP + CONFIG_STM32_USART1_REMAP + CONFIG_STM32_USART2_REMAP + CONFIG_STM32_USART3_FULL_REMAP + CONFIG_STM32_USART3_PARTIAL_REMAP + CONFIG_STM32_SPI1_REMAP + CONFIG_STM32_SPI3_REMAP + CONFIG_STM32_I2C1_REMAP + CONFIG_STM32_CAN1_REMAP1 + CONFIG_STM32_CAN1_REMAP2 + CONFIG_STM32_CAN2_REMAP STM32F103V specific device driver settings - CONFIG_U[S]ARTn_SERIAL_CONSOLE - selects the USARTn (n=1,2,3) or UART + CONFIG_U[S]ARTn_SERIAL_CONSOLE - selects the USARTn (n=1,2,3) or UART m (m=4,5) for the console and ttys0 (default is the USART1). Note: USART1 is connected to a PL2303 serial to USB converter. So USART1 is available through USB port labeled CN3 on the board. - CONFIG_U[S]ARTn_RXBUFSIZE - Characters are buffered as received. - This specific the size of the receive buffer - CONFIG_U[S]ARTn_TXBUFSIZE - Characters are buffered before - being sent. This specific the size of the transmit buffer - CONFIG_U[S]ARTn_BAUD - The configure BAUD of the UART. Must be - CONFIG_U[S]ARTn_BITS - The number of bits. Must be either 7 or 8. - CONFIG_U[S]ARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity - CONFIG_U[S]ARTn_2STOP - Two stop bits - - CONFIG_STM32_SPI_INTERRUPTS - Select to enable interrupt driven SPI - support. Non-interrupt-driven, poll-waiting is recommended if the - interrupt rate would be to high in the interrupt driven case. - CONFIG_STM32_SPI_DMA - Use DMA to improve SPI transfer performance. - Cannot be used with CONFIG_STM32_SPI_INTERRUPT. - - CONFIG_SDIO_DMA - Support DMA data transfers. Requires CONFIG_STM32_SDIO - and CONFIG_STM32_DMA2. - CONFIG_SDIO_PRI - Select SDIO interrupt prority. Default: 128 - CONFIG_SDIO_DMAPRIO - Select SDIO DMA interrupt priority. - Default: Medium - CONFIG_SDIO_WIDTH_D1_ONLY - Select 1-bit transfer mode. Default: - 4-bit transfer mode. + CONFIG_U[S]ARTn_RXBUFSIZE - Characters are buffered as received. + This specific the size of the receive buffer + CONFIG_U[S]ARTn_TXBUFSIZE - Characters are buffered before + being sent. This specific the size of the transmit buffer + CONFIG_U[S]ARTn_BAUD - The configure BAUD of the UART. Must be + CONFIG_U[S]ARTn_BITS - The number of bits. Must be either 7 or 8. + CONFIG_U[S]ARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity + CONFIG_U[S]ARTn_2STOP - Two stop bits + + CONFIG_STM32_SPI_INTERRUPTS - Select to enable interrupt driven SPI + support. Non-interrupt-driven, poll-waiting is recommended if the + interrupt rate would be to high in the interrupt driven case. + CONFIG_STM32_SPI_DMA - Use DMA to improve SPI transfer performance. + Cannot be used with CONFIG_STM32_SPI_INTERRUPT. + + CONFIG_SDIO_DMA - Support DMA data transfers. Requires CONFIG_STM32_SDIO + and CONFIG_STM32_DMA2. + CONFIG_SDIO_PRI - Select SDIO interrupt prority. Default: 128 + CONFIG_SDIO_DMAPRIO - Select SDIO DMA interrupt priority. + Default: Medium + CONFIG_SDIO_WIDTH_D1_ONLY - Select 1-bit transfer mode. Default: + 4-bit transfer mode. CONFIG_MMCSD_HAVECARDDETECT - Select if SDIO driver card detection is 100% accurate (it is on the HY-MiniSTM32V) HY-MiniSTM32V CAN Configuration - CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or - CONFIG_STM32_CAN2 must also be defined) - CONFIG_CAN_EXTID - Enables support for the 29-bit extended ID. Default - Standard 11-bit IDs. - CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages. - Default: 8 - CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests. - Default: 4 - CONFIG_CAN_LOOPBACK - A CAN driver may or may not support a loopback - mode for testing. The STM32 CAN driver does support loopback mode. - CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN1 is defined. - CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 is defined. - CONFIG_CAN_TSEG1 - The number of CAN time quanta in segment 1. Default: 6 - CONFIG_CAN_TSEG2 - the number of CAN time quanta in segment 2. Default: 7 - CONFIG_CAN_REGDEBUG - If CONFIG_DEBUG is set, this will generate an - dump of all CAN registers. + CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or + CONFIG_STM32_CAN2 must also be defined) + CONFIG_CAN_EXTID - Enables support for the 29-bit extended ID. Default + Standard 11-bit IDs. + CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages. + Default: 8 + CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests. + Default: 4 + CONFIG_CAN_LOOPBACK - A CAN driver may or may not support a loopback + mode for testing. The STM32 CAN driver does support loopback mode. + CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN1 is defined. + CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 is defined. + CONFIG_CAN_TSEG1 - The number of CAN time quanta in segment 1. Default: 6 + CONFIG_CAN_TSEG2 - the number of CAN time quanta in segment 2. Default: 7 + CONFIG_CAN_REGDEBUG - If CONFIG_DEBUG is set, this will generate an + dump of all CAN registers. HY-MiniSTM32V LCD Hardware Configuration (SSD1289 controler) @@ -510,10 +562,10 @@ Configurations Each HY-MiniSTM32V configuration is maintained in a sudirectory and can be selected as follow: - cd tools - ./configure.sh hymini-stm32v/ - cd - - . ./setenv.sh + cd tools + ./configure.sh hymini-stm32v/ + cd - + . ./setenv.sh Where is one of the following: @@ -547,10 +599,10 @@ Where is one of the following: FAT FS CONFIG_FAT_LCNAME=y CONFIG_FAT_LCNAME=y Config CONFIG_FAT_LFN=n CONFIG_FAT_LFN=y (4) ----------- ----------------------- -------------------------------- - LCD Driver No Yes - Support + LCD Driver No Yes + Support ----------- ----------------------- -------------------------------- - RTC Support No Yes + RTC Support No Yes ----------- ----------------------- -------------------------------- Support for No Yes Built-in diff --git a/nuttx/configs/kwikstik-k40/README.txt b/nuttx/configs/kwikstik-k40/README.txt index a268a52d8..a320cbb05 100644 --- a/nuttx/configs/kwikstik-k40/README.txt +++ b/nuttx/configs/kwikstik-k40/README.txt @@ -22,7 +22,9 @@ Contents o Development Environment o GNU Toolchain Options o IDEs - o NuttX buildroot Toolchain + o NuttX EABI "buildroot" Toolchain + o NuttX OABI "buildroot" Toolchain + o NXFLAT Toolchain Kinetis KwikStik-K40 Features: ============================== @@ -171,7 +173,7 @@ GNU Toolchain Options CONFIG_KINETIS_CODESOURCERYW=y : CodeSourcery under Windows CONFIG_KINETIS_CODESOURCERYL=y : CodeSourcery under Linux CONFIG_KINETIS_DEVKITARM=y : devkitARM under Windows - CONFIG_KINETIS_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default) + CONFIG_KINETIS_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default) If you are not using CONFIG_KINETIS_BUILDROOT, then you may also have to modify the PATH in the setenv.h file if your make cannot find the tools. @@ -249,8 +251,8 @@ IDEs Startup files will probably cause you some headaches. The NuttX startup file is arch/arm/src/kinetis/k40_vectors.S. -NuttX buildroot Toolchain -========================= +NuttX EABI "buildroot" Toolchain +================================ A GNU GCC-based toolchain is assumed. The files */setenv.sh should be modified to point to the correct path to the Cortex-M4 GCC toolchain (if @@ -260,8 +262,7 @@ NuttX buildroot Toolchain SourceForge download site (https://sourceforge.net/projects/nuttx/files/buildroot/). This GNU toolchain builds and executes in the Linux or Cygwin environment. - NOTE: The NuttX toolchain is an OABI toolchain (vs. the more common EABI) - and does not include optimizations for Cortex-M4 (ARMv7E-M). + NOTE: The NuttX toolchain may not include optimizations for Cortex-M4 (ARMv7E-M). 1. You must have already configured Nuttx in /nuttx. @@ -276,7 +277,7 @@ NuttX buildroot Toolchain 4. cd /buildroot - 5. cp configs/cortexm3-defconfig-4.3.3 .config + 5. cp configs/cortexm3-eabi-defconfig-4.6.3 .config 6. make oldconfig @@ -286,92 +287,142 @@ NuttX buildroot Toolchain the path to the newly built binaries. See the file configs/README.txt in the buildroot source tree. That has more - detailed PLUS some special instructions that you will need to follow if you are + details PLUS some special instructions that you will need to follow if you are building a Cortex-M4 toolchain for Cygwin under Windows. +NuttX OABI "buildroot" Toolchain +================================ + + The older, OABI buildroot toolchain is also available. To use the OABI + toolchain: + + 1. When building the buildroot toolchain, either (1) modify the cortexm3-eabi-defconfig-4.6.3 + configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI + configuration such as cortexm3-defconfig-4.3.3 + + 2. Modify the Make.defs file to use the OABI converntions: + + +CROSSDEV = arm-nuttx-elf- + +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + -CROSSDEV = arm-nuttx-eabi- + -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + +NXFLAT Toolchain +================ + + If you are *not* using the NuttX buildroot toolchain and you want to use + the NXFLAT tools, then you will still have to build a portion of the buildroot + tools -- just the NXFLAT tools. The buildroot with the NXFLAT tools can + be downloaded from the NuttX SourceForge download site + (https://sourceforge.net/projects/nuttx/files/). + + This GNU toolchain builds and executes in the Linux or Cygwin environment. + + 1. You must have already configured Nuttx in /nuttx. + + cd tools + ./configure.sh lpcxpresso-lpc1768/ + + 2. Download the latest buildroot package into + + 3. unpack the buildroot tarball. The resulting directory may + have versioning information on it like buildroot-x.y.z. If so, + rename /buildroot-x.y.z to /buildroot. + + 4. cd /buildroot + + 5. cp configs/cortexm3-defconfig-nxflat .config + + 6. make oldconfig + + 7. make + + 8. Edit setenv.h, if necessary, so that the PATH variable includes + the path to the newly builtNXFLAT binaries. + KwikStik-K40-specific Configuration Options ============================================ - CONFIG_ARCH - Identifies the arch/ subdirectory. This sould - be set to: + CONFIG_ARCH - Identifies the arch/ subdirectory. This sould + be set to: - CONFIG_ARCH=arm + CONFIG_ARCH=arm - CONFIG_ARCH_family - For use in C code: + CONFIG_ARCH_family - For use in C code: - CONFIG_ARCH_ARM=y + CONFIG_ARCH_ARM=y - CONFIG_ARCH_architecture - For use in C code: + CONFIG_ARCH_architecture - For use in C code: - CONFIG_ARCH_CORTEXM4=y + CONFIG_ARCH_CORTEXM4=y - CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory + CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory - CONFIG_ARCH_CHIP=k40 + CONFIG_ARCH_CHIP=k40 - CONFIG_ARCH_CHIP_name - For use in C code to identify the exact - chip: + CONFIG_ARCH_CHIP_name - For use in C code to identify the exact + chip: - CONFIG_ARCH_CHIP_MK40X256VLQ100 + CONFIG_ARCH_CHIP_MK40X256VLQ100 - CONFIG_ARCH_BOARD - Identifies the configs subdirectory and - hence, the board that supports the particular chip or SoC. + CONFIG_ARCH_BOARD - Identifies the configs subdirectory and + hence, the board that supports the particular chip or SoC. - CONFIG_ARCH_BOARD=kwikstik-k40 (for the KwikStik-K40 development board) + CONFIG_ARCH_BOARD=kwikstik-k40 (for the KwikStik-K40 development board) - CONFIG_ARCH_BOARD_name - For use in C code + CONFIG_ARCH_BOARD_name - For use in C code - CONFIG_ARCH_BOARD_KWIKSTIK_K40=y + CONFIG_ARCH_BOARD_KWIKSTIK_K40=y - CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation - of delay loops + CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation + of delay loops - CONFIG_ENDIAN_BIG - define if big endian (default is little - endian) + CONFIG_ENDIAN_BIG - define if big endian (default is little + endian) - CONFIG_DRAM_SIZE - Describes the installed DRAM (SRAM in this case): + CONFIG_DRAM_SIZE - Describes the installed DRAM (SRAM in this case): - CONFIG_DRAM_SIZE=0x00010000 (64Kb) + CONFIG_DRAM_SIZE=0x00010000 (64Kb) - CONFIG_DRAM_START - The start address of installed DRAM + CONFIG_DRAM_START - The start address of installed DRAM - CONFIG_DRAM_START=0x20000000 + CONFIG_DRAM_START=0x20000000 - CONFIG_ARCH_IRQPRIO - The Kinetis K40 supports interrupt prioritization + CONFIG_ARCH_IRQPRIO - The Kinetis K40 supports interrupt prioritization - CONFIG_ARCH_IRQPRIO=y + CONFIG_ARCH_IRQPRIO=y - CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that - have LEDs + CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that + have LEDs - CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt - stack. If defined, this symbol is the size of the interrupt - stack in bytes. If not defined, the user task stacks will be - used during interrupt handling. + CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt + stack. If defined, this symbol is the size of the interrupt + stack in bytes. If not defined, the user task stacks will be + used during interrupt handling. - CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions + CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions - CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. + CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. - CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that - cause a 100 second delay during boot-up. This 100 second delay - serves no purpose other than it allows you to calibratre - CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure - the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until - the delay actually is 100 seconds. + CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that + cause a 100 second delay during boot-up. This 100 second delay + serves no purpose other than it allows you to calibratre + CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure + the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until + the delay actually is 100 seconds. Individual subsystems can be enabled: CONFIG_KINETIS_TRACE -- Enable trace clocking on power up. CONFIG_KINETIS_FLEXBUS -- Enable flexbus clocking on power up. - CONFIG_KINETIS_UART0 -- Support UART0 - CONFIG_KINETIS_UART1 -- Support UART1 - CONFIG_KINETIS_UART2 -- Support UART2 - CONFIG_KINETIS_UART3 -- Support UART3 - CONFIG_KINETIS_UART4 -- Support UART4 - CONFIG_KINETIS_UART5 -- Support UART5 - CONFIG_KINETIS_ENET -- Support Ethernet (K60 only) - CONFIG_KINETIS_RNGB -- Support the random number generator(K60 only) + CONFIG_KINETIS_UART0 -- Support UART0 + CONFIG_KINETIS_UART1 -- Support UART1 + CONFIG_KINETIS_UART2 -- Support UART2 + CONFIG_KINETIS_UART3 -- Support UART3 + CONFIG_KINETIS_UART4 -- Support UART4 + CONFIG_KINETIS_UART5 -- Support UART5 + CONFIG_KINETIS_ENET -- Support Ethernet (K60 only) + CONFIG_KINETIS_RNGB -- Support the random number generator(K60 only) CONFIG_KINETIS_FLEXCAN0 -- Support FlexCAN0 CONFIG_KINETIS_FLEXCAN1 -- Support FlexCAN1 CONFIG_KINETIS_SPI0 -- Support SPI0 @@ -380,8 +431,8 @@ KwikStik-K40-specific Configuration Options CONFIG_KINETIS_I2C0 -- Support I2C0 CONFIG_KINETIS_I2C1 -- Support I2C1 CONFIG_KINETIS_I2S -- Support I2S - CONFIG_KINETIS_DAC0 -- Support DAC0 - CONFIG_KINETIS_DAC1 -- Support DAC1 + CONFIG_KINETIS_DAC0 -- Support DAC0 + CONFIG_KINETIS_DAC1 -- Support DAC1 CONFIG_KINETIS_ADC0 -- Support ADC0 CONFIG_KINETIS_ADC1 -- Support ADC1 CONFIG_KINETIS_CMP -- Support CMP @@ -429,15 +480,15 @@ KwikStik-K40-specific Configuration Options Kinetis K40 specific device driver settings - CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn (n=0..5) for the + CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn (n=0..5) for the console and ttys0 (default is the UART0). - CONFIG_UARTn_RXBUFSIZE - Characters are buffered as received. - This specific the size of the receive buffer - CONFIG_UARTn_TXBUFSIZE - Characters are buffered before - being sent. This specific the size of the transmit buffer - CONFIG_UARTn_BAUD - The configure BAUD of the UART. - CONFIG_UARTn_BITS - The number of bits. Must be either 8 or 8. - CONFIG_UARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity + CONFIG_UARTn_RXBUFSIZE - Characters are buffered as received. + This specific the size of the receive buffer + CONFIG_UARTn_TXBUFSIZE - Characters are buffered before + being sent. This specific the size of the transmit buffer + CONFIG_UARTn_BAUD - The configure BAUD of the UART. + CONFIG_UARTn_BITS - The number of bits. Must be either 8 or 8. + CONFIG_UARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity KwikStik-K40 LCD Hardware Configuration @@ -462,10 +513,10 @@ Configurations Each KwikStik-K40 configuration is maintained in a sudirectory and can be selected as follow: - cd tools - ./configure.sh kwikstik-k40/ - cd - - . ./setenv.sh + cd tools + ./configure.sh kwikstik-k40/ + cd - + . ./setenv.sh Where is one of the following: @@ -475,4 +526,4 @@ Where is one of the following: examples/ostest. By default, this project assumes that you are using the DFU bootloader. - CONFIG_KINETIS_BUILDROOT=y : NuttX buildroot under Linux or Cygwin + CONFIG_KINETIS_BUILDROOT=y : NuttX buildroot under Linux or Cygwin diff --git a/nuttx/configs/lincoln60/README.txt b/nuttx/configs/lincoln60/README.txt index a699d5f33..abbc57204 100644 --- a/nuttx/configs/lincoln60/README.txt +++ b/nuttx/configs/lincoln60/README.txt @@ -10,7 +10,9 @@ Contents Development Environment GNU Toolchain Options IDEs - NuttX buildroot Toolchain + NuttX EABI "buildroot" Toolchain + NuttX OABI "buildroot" Toolchain + NXFLAT Toolchain USB Device Controller Functions Lincoln 60 Configuration Options USB Host Configuration @@ -150,8 +152,8 @@ IDEs Startup files will probably cause you some headaches. The NuttX startup file is arch/arm/src/lpc17x/lpc17_vectors.S. -NuttX buildroot Toolchain -^^^^^^^^^^^^^^^^^^^^^^^^^ +NuttX EABI "buildroot" Toolchain +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ A GNU GCC-based toolchain is assumed. The files */setenv.sh should be modified to point to the correct path to the Cortex-M3 GCC toolchain (if @@ -174,7 +176,7 @@ NuttX buildroot Toolchain 4. cd /buildroot - 5. cp configs/cortexm3-defconfig-4.3.3 .config + 5. cp configs/cortexm3-eabi-defconfig-4.6.3 .config 6. make oldconfig @@ -184,184 +186,232 @@ NuttX buildroot Toolchain the path to the newly built binaries. See the file configs/README.txt in the buildroot source tree. That has more - detailed PLUS some special instructions that you will need to follow if you + details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. - NOTE: This is an OABI toolchain. +NuttX OABI "buildroot" Toolchain +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + + The older, OABI buildroot toolchain is also available. To use the OABI + toolchain: + + 1. When building the buildroot toolchain, either (1) modify the cortexm3-eabi-defconfig-4.6.3 + configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI + configuration such as cortexm3-defconfig-4.3.3 + + 2. Modify the Make.defs file to use the OABI converntions: + + +CROSSDEV = arm-nuttx-elf- + +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + -CROSSDEV = arm-nuttx-eabi- + -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + +NXFLAT Toolchain +^^^^^^^^^^^^^^^^ + + If you are *not* using the NuttX buildroot toolchain and you want to use + the NXFLAT tools, then you will still have to build a portion of the buildroot + tools -- just the NXFLAT tools. The buildroot with the NXFLAT tools can + be downloaded from the NuttX SourceForge download site + (https://sourceforge.net/projects/nuttx/files/). + + This GNU toolchain builds and executes in the Linux or Cygwin environment. + + 1. You must have already configured Nuttx in /nuttx. + + cd tools + ./configure.sh lpcxpresso-lpc1768/ + + 2. Download the latest buildroot package into + + 3. unpack the buildroot tarball. The resulting directory may + have versioning information on it like buildroot-x.y.z. If so, + rename /buildroot-x.y.z to /buildroot. + + 4. cd /buildroot + + 5. cp configs/cortexm3-defconfig-nxflat .config + + 6. make oldconfig + + 7. make + + 8. Edit setenv.h, if necessary, so that the PATH variable includes + the path to the newly builtNXFLAT binaries. Lincoln 60 Configuration Options ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - CONFIG_ARCH - Identifies the arch/ subdirectory. This should - be set to: + CONFIG_ARCH - Identifies the arch/ subdirectory. This should + be set to: - CONFIG_ARCH=arm + CONFIG_ARCH=arm - CONFIG_ARCH_family - For use in C code: + CONFIG_ARCH_family - For use in C code: - CONFIG_ARCH_ARM=y + CONFIG_ARCH_ARM=y - CONFIG_ARCH_architecture - For use in C code: + CONFIG_ARCH_architecture - For use in C code: - CONFIG_ARCH_CORTEXM3=y + CONFIG_ARCH_CORTEXM3=y - CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory + CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory - CONFIG_ARCH_CHIP=lpc17xx + CONFIG_ARCH_CHIP=lpc17xx - CONFIG_ARCH_CHIP_name - For use in C code to identify the exact - chip: + CONFIG_ARCH_CHIP_name - For use in C code to identify the exact + chip: - CONFIG_ARCH_CHIP_LPC1768=y + CONFIG_ARCH_CHIP_LPC1768=y - CONFIG_ARCH_BOARD - Identifies the configs subdirectory and - hence, the board that supports the particular chip or SoC. + CONFIG_ARCH_BOARD - Identifies the configs subdirectory and + hence, the board that supports the particular chip or SoC. - CONFIG_ARCH_BOARD=lincoln60 (for the Lincoln 60 board) + CONFIG_ARCH_BOARD=lincoln60 (for the Lincoln 60 board) - CONFIG_ARCH_BOARD_name - For use in C code + CONFIG_ARCH_BOARD_name - For use in C code - CONFIG_ARCH_BOARD_LINCOLN60=y + CONFIG_ARCH_BOARD_LINCOLN60=y - CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation - of delay loops + CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation + of delay loops - CONFIG_ENDIAN_BIG - define if big endian (default is little - endian) + CONFIG_ENDIAN_BIG - define if big endian (default is little + endian) - CONFIG_DRAM_SIZE - Describes the installed DRAM (CPU SRAM in this case): + CONFIG_DRAM_SIZE - Describes the installed DRAM (CPU SRAM in this case): - CONFIG_DRAM_SIZE=(32*1024) (32Kb) + CONFIG_DRAM_SIZE=(32*1024) (32Kb) - There is an additional 32Kb of SRAM in AHB SRAM banks 0 and 1. + There is an additional 32Kb of SRAM in AHB SRAM banks 0 and 1. - CONFIG_DRAM_START - The start address of installed DRAM + CONFIG_DRAM_START - The start address of installed DRAM - CONFIG_DRAM_START=0x10000000 + CONFIG_DRAM_START=0x10000000 - CONFIG_ARCH_IRQPRIO - The LPC17xx supports interrupt prioritization + CONFIG_ARCH_IRQPRIO - The LPC17xx supports interrupt prioritization - CONFIG_ARCH_IRQPRIO=y + CONFIG_ARCH_IRQPRIO=y - CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that - have LEDs + CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that + have LEDs - CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt - stack. If defined, this symbol is the size of the interrupt - stack in bytes. If not defined, the user task stacks will be - used during interrupt handling. + CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt + stack. If defined, this symbol is the size of the interrupt + stack in bytes. If not defined, the user task stacks will be + used during interrupt handling. - CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions + CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions - CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. + CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. - CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that - cause a 100 second delay during boot-up. This 100 second delay - serves no purpose other than it allows you to calibratre - CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure - the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until - the delay actually is 100 seconds. + CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that + cause a 100 second delay during boot-up. This 100 second delay + serves no purpose other than it allows you to calibratre + CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure + the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until + the delay actually is 100 seconds. - Individual subsystems can be enabled: - CONFIG_LPC17_MAINOSC=y - CONFIG_LPC17_PLL0=y - CONFIG_LPC17_PLL1=n - CONFIG_LPC17_ETHERNET=n - CONFIG_LPC17_USBHOST=n - CONFIG_LPC17_USBOTG=n - CONFIG_LPC17_USBDEV=n - CONFIG_LPC17_UART0=y - CONFIG_LPC17_UART1=n - CONFIG_LPC17_UART2=n - CONFIG_LPC17_UART3=n - CONFIG_LPC17_CAN1=n - CONFIG_LPC17_CAN2=n - CONFIG_LPC17_SPI=n - CONFIG_LPC17_SSP0=n - CONFIG_LPC17_SSP1=n - CONFIG_LPC17_I2C0=n - CONFIG_LPC17_I2C1=n - CONFIG_LPC17_I2S=n - CONFIG_LPC17_TMR0=n - CONFIG_LPC17_TMR1=n - CONFIG_LPC17_TMR2=n - CONFIG_LPC17_TMR3=n - CONFIG_LPC17_RIT=n - CONFIG_LPC17_PWM=n - CONFIG_LPC17_MCPWM=n - CONFIG_LPC17_QEI=n - CONFIG_LPC17_RTC=n - CONFIG_LPC17_WDT=n - CONFIG_LPC17_ADC=n - CONFIG_LPC17_DAC=n - CONFIG_LPC17_GPDMA=n - CONFIG_LPC17_FLASH=n + Individual subsystems can be enabled: + CONFIG_LPC17_MAINOSC=y + CONFIG_LPC17_PLL0=y + CONFIG_LPC17_PLL1=n + CONFIG_LPC17_ETHERNET=n + CONFIG_LPC17_USBHOST=n + CONFIG_LPC17_USBOTG=n + CONFIG_LPC17_USBDEV=n + CONFIG_LPC17_UART0=y + CONFIG_LPC17_UART1=n + CONFIG_LPC17_UART2=n + CONFIG_LPC17_UART3=n + CONFIG_LPC17_CAN1=n + CONFIG_LPC17_CAN2=n + CONFIG_LPC17_SPI=n + CONFIG_LPC17_SSP0=n + CONFIG_LPC17_SSP1=n + CONFIG_LPC17_I2C0=n + CONFIG_LPC17_I2C1=n + CONFIG_LPC17_I2S=n + CONFIG_LPC17_TMR0=n + CONFIG_LPC17_TMR1=n + CONFIG_LPC17_TMR2=n + CONFIG_LPC17_TMR3=n + CONFIG_LPC17_RIT=n + CONFIG_LPC17_PWM=n + CONFIG_LPC17_MCPWM=n + CONFIG_LPC17_QEI=n + CONFIG_LPC17_RTC=n + CONFIG_LPC17_WDT=n + CONFIG_LPC17_ADC=n + CONFIG_LPC17_DAC=n + CONFIG_LPC17_GPDMA=n + CONFIG_LPC17_FLASH=n LPC17xx specific device driver settings - CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn for the - console and ttys0 (default is the UART0). - CONFIG_UARTn_RXBUFSIZE - Characters are buffered as received. - This specific the size of the receive buffer - CONFIG_UARTn_TXBUFSIZE - Characters are buffered before - being sent. This specific the size of the transmit buffer - CONFIG_UARTn_BAUD - The configure BAUD of the UART. Must be - CONFIG_UARTn_BITS - The number of bits. Must be either 7 or 8. - CONFIG_UARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity - CONFIG_UARTn_2STOP - Two stop bits + CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn for the + console and ttys0 (default is the UART0). + CONFIG_UARTn_RXBUFSIZE - Characters are buffered as received. + This specific the size of the receive buffer + CONFIG_UARTn_TXBUFSIZE - Characters are buffered before + being sent. This specific the size of the transmit buffer + CONFIG_UARTn_BAUD - The configure BAUD of the UART. Must be + CONFIG_UARTn_BITS - The number of bits. Must be either 7 or 8. + CONFIG_UARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity + CONFIG_UARTn_2STOP - Two stop bits LPC17xx specific CAN device driver settings. These settings all require CONFIG_CAN: - CONFIG_CAN_EXTID - Enables support for the 29-bit extended ID. Default - Standard 11-bit IDs. - CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN1 is defined. - CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN2 is defined. - CONFIG_CAN1_DIVISOR - CAN1 is clocked at CCLK divided by this number. - (the CCLK frequency is divided by this number to get the CAN clock). - Options = {1,2,4,6}. Default: 4. - CONFIG_CAN2_DIVISOR - CAN2 is clocked at CCLK divided by this number. - (the CCLK frequency is divided by this number to get the CAN clock). - Options = {1,2,4,6}. Default: 4. - CONFIG_CAN_TSEG1 - The number of CAN time quanta in segment 1. Default: 6 - CONFIG_CAN_TSEG2 = the number of CAN time quanta in segment 2. Default: 7 + CONFIG_CAN_EXTID - Enables support for the 29-bit extended ID. Default + Standard 11-bit IDs. + CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN1 is defined. + CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN2 is defined. + CONFIG_CAN1_DIVISOR - CAN1 is clocked at CCLK divided by this number. + (the CCLK frequency is divided by this number to get the CAN clock). + Options = {1,2,4,6}. Default: 4. + CONFIG_CAN2_DIVISOR - CAN2 is clocked at CCLK divided by this number. + (the CCLK frequency is divided by this number to get the CAN clock). + Options = {1,2,4,6}. Default: 4. + CONFIG_CAN_TSEG1 - The number of CAN time quanta in segment 1. Default: 6 + CONFIG_CAN_TSEG2 = the number of CAN time quanta in segment 2. Default: 7 LPC17xx specific PHY/Ethernet device driver settings. These setting also require CONFIG_NET and CONFIG_LPC17_ETHERNET. - CONFIG_PHY_KS8721 - Selects Micrel KS8721 PHY - CONFIG_PHY_AUTONEG - Enable auto-negotion - CONFIG_PHY_SPEED100 - Select 100Mbit vs. 10Mbit speed. - CONFIG_PHY_FDUPLEX - Select full (vs. half) duplex + CONFIG_PHY_KS8721 - Selects Micrel KS8721 PHY + CONFIG_PHY_AUTONEG - Enable auto-negotion + CONFIG_PHY_SPEED100 - Select 100Mbit vs. 10Mbit speed. + CONFIG_PHY_FDUPLEX - Select full (vs. half) duplex CONFIG_NET_EMACRAM_SIZE - Size of EMAC RAM. Default: 16Kb - CONFIG_NET_NTXDESC - Configured number of Tx descriptors. Default: 18 - CONFIG_NET_NRXDESC - Configured number of Rx descriptors. Default: 18 - CONFIG_NET_PRIORITY - Ethernet interrupt priority. The is default is - the higest priority. - CONFIG_NET_WOL - Enable Wake-up on Lan (not fully implemented). - CONFIG_NET_REGDEBUG - Enabled low level register debug. Also needs - CONFIG_DEBUG. - CONFIG_NET_DUMPPACKET - Dump all received and transmitted packets. - Also needs CONFIG_DEBUG. - CONFIG_NET_HASH - Enable receipt of near-perfect match frames. - CONFIG_NET_MULTICAST - Enable receipt of multicast (and unicast) frames. + CONFIG_NET_NTXDESC - Configured number of Tx descriptors. Default: 18 + CONFIG_NET_NRXDESC - Configured number of Rx descriptors. Default: 18 + CONFIG_NET_PRIORITY - Ethernet interrupt priority. The is default is + the higest priority. + CONFIG_NET_WOL - Enable Wake-up on Lan (not fully implemented). + CONFIG_NET_REGDEBUG - Enabled low level register debug. Also needs + CONFIG_DEBUG. + CONFIG_NET_DUMPPACKET - Dump all received and transmitted packets. + Also needs CONFIG_DEBUG. + CONFIG_NET_HASH - Enable receipt of near-perfect match frames. + CONFIG_NET_MULTICAST - Enable receipt of multicast (and unicast) frames. Automatically set if CONFIG_NET_IGMP is selected. LPC17xx USB Device Configuration - CONFIG_LPC17_USBDEV_FRAME_INTERRUPT - Handle USB Start-Of-Frame events. - Enable reading SOF from interrupt handler vs. simply reading on demand. - Probably a bad idea... Unless there is some issue with sampling the SOF - from hardware asynchronously. - CONFIG_LPC17_USBDEV_EPFAST_INTERRUPT - Enable high priority interrupts. I have no idea why you might want to - do that - CONFIG_LPC17_USBDEV_NDMADESCRIPTORS - Number of DMA descriptors to allocate in SRAM. - CONFIG_LPC17_USBDEV_DMA - Enable lpc17xx-specific DMA support + CONFIG_LPC17_USBDEV_FRAME_INTERRUPT + Handle USB Start-Of-Frame events. + Enable reading SOF from interrupt handler vs. simply reading on demand. + Probably a bad idea... Unless there is some issue with sampling the SOF + from hardware asynchronously. + CONFIG_LPC17_USBDEV_EPFAST_INTERRUPT + Enable high priority interrupts. I have no idea why you might want to + do that + CONFIG_LPC17_USBDEV_NDMADESCRIPTORS + Number of DMA descriptors to allocate in SRAM. + CONFIG_LPC17_USBDEV_DMA + Enable lpc17xx-specific DMA support CONFIG_LPC17_USBDEV_NOVBUS Define if the hardware implementation does not support the VBUS signal CONFIG_LPC17_USBDEV_NOLED @@ -425,10 +475,10 @@ Configurations Each Lincoln 60 configuration is maintained in a sudirectory and can be selected as follow: - cd tools - ./configure.sh lincoln60/ - cd - - . ./setenv.sh + cd tools + ./configure.sh lincoln60/ + cd - + . ./setenv.sh Where is one of the following: diff --git a/nuttx/configs/lm3s6432-s2e/README.txt b/nuttx/configs/lm3s6432-s2e/README.txt index 2266e99e2..10ceda15a 100644 --- a/nuttx/configs/lm3s6432-s2e/README.txt +++ b/nuttx/configs/lm3s6432-s2e/README.txt @@ -11,7 +11,9 @@ Contents Development Environment GNU Toolchain Options IDEs - NuttX buildroot Toolchain + NuttX EABI "buildroot" Toolchain + NuttX OABI "buildroot" Toolchain + NXFLFAT Toolchain Stellaris MDL-S2E Reference Design Configuration Options Configurations @@ -176,8 +178,8 @@ IDEs Startup files will probably cause you some headaches. The NuttX startup file is arch/arm/src/lm3s/lm3s_vectors.S. -NuttX buildroot Toolchain -^^^^^^^^^^^^^^^^^^^^^^^^^ +NuttX EABI "buildroot" Toolchain +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ A GNU GCC-based toolchain is assumed. The files */setenv.sh should be modified to point to the correct path to the Cortex-M3 GCC toolchain (if @@ -204,7 +206,7 @@ NuttX buildroot Toolchain 4. cd /buildroot - 5. cp configs/cortexm3-defconfig-4.3.3 .config + 5. cp configs/cortexm3-eabi-defconfig-4.6.3 .config 6. make oldconfig @@ -214,142 +216,189 @@ NuttX buildroot Toolchain the path to the newly built binaries. See the file configs/README.txt in the buildroot source tree. That has more - detailed PLUS some special instructions that you will need to follow if you + details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. - NOTE: This is an OABI toolchain. +NuttX OABI "buildroot" Toolchain +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + The older, OABI buildroot toolchain is also available. To use the OABI + toolchain: + + 1. When building the buildroot toolchain, either (1) modify the cortexm3-eabi-defconfig-4.6.3 + configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI + configuration such as cortexm3-defconfig-4.3.3 + + 2. Modify the Make.defs file to use the OABI converntions: + + +CROSSDEV = arm-nuttx-elf- + +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + -CROSSDEV = arm-nuttx-eabi- + -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + +NXFLAT Toolchain +^^^^^^^^^^^^^^^^ + + If you are *not* using the NuttX buildroot toolchain and you want to use + the NXFLAT tools, then you will still have to build a portion of the buildroot + tools -- just the NXFLAT tools. The buildroot with the NXFLAT tools can + be downloaded from the NuttX SourceForge download site + (https://sourceforge.net/projects/nuttx/files/). + + This GNU toolchain builds and executes in the Linux or Cygwin environment. + + 1. You must have already configured Nuttx in /nuttx. + + cd tools + ./configure.sh lpcxpresso-lpc1768/ + + 2. Download the latest buildroot package into + + 3. unpack the buildroot tarball. The resulting directory may + have versioning information on it like buildroot-x.y.z. If so, + rename /buildroot-x.y.z to /buildroot. + + 4. cd /buildroot + + 5. cp configs/cortexm3-defconfig-nxflat .config + + 6. make oldconfig + + 7. make + + 8. Edit setenv.h, if necessary, so that the PATH variable includes + the path to the newly builtNXFLAT binaries. Stellaris MDL-S2E Reference Design Configuration Options ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - CONFIG_ARCH - Identifies the arch/ subdirectory. This should - be set to: + CONFIG_ARCH - Identifies the arch/ subdirectory. This should + be set to: - CONFIG_ARCH=arm + CONFIG_ARCH=arm - CONFIG_ARCH_family - For use in C code: + CONFIG_ARCH_family - For use in C code: - CONFIG_ARCH_ARM=y + CONFIG_ARCH_ARM=y - CONFIG_ARCH_architecture - For use in C code: + CONFIG_ARCH_architecture - For use in C code: - CONFIG_ARCH_CORTEXM3=y + CONFIG_ARCH_CORTEXM3=y - CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory + CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory - CONFIG_ARCH_CHIP=lm3s + CONFIG_ARCH_CHIP=lm3s - CONFIG_ARCH_CHIP_name - For use in C code to identify the exact - chip: + CONFIG_ARCH_CHIP_name - For use in C code to identify the exact + chip: - CONFIG_ARCH_CHIP_LM3S6432 + CONFIG_ARCH_CHIP_LM3S6432 - CONFIG_ARCH_BOARD - Identifies the configs subdirectory and - hence, the board that supports the particular chip or SoC. + CONFIG_ARCH_BOARD - Identifies the configs subdirectory and + hence, the board that supports the particular chip or SoC. - CONFIG_ARCH_BOARD=lm3s6432-s2e (for the Stellaris MDL-S2E Reference Design) + CONFIG_ARCH_BOARD=lm3s6432-s2e (for the Stellaris MDL-S2E Reference Design) - CONFIG_ARCH_BOARD_name - For use in C code + CONFIG_ARCH_BOARD_name - For use in C code - CONFIG_ARCH_BOARD_LM3S6432S2E + CONFIG_ARCH_BOARD_LM3S6432S2E - CONFIG_ARCH_LOOPSPERMSEC - As supplied, calibrated for correct operation - of delay loops assuming 50MHz CPU frequency. + CONFIG_ARCH_LOOPSPERMSEC - As supplied, calibrated for correct operation + of delay loops assuming 50MHz CPU frequency. - CONFIG_ENDIAN_BIG - define if big endian (default is little - endian) + CONFIG_ENDIAN_BIG - define if big endian (default is little + endian) - CONFIG_DRAM_SIZE - Describes the installed DRAM (SRAM in this case): + CONFIG_DRAM_SIZE - Describes the installed DRAM (SRAM in this case): - CONFIG_DRAM_SIZE=0x00010000 (64Kb) + CONFIG_DRAM_SIZE=0x00010000 (64Kb) - CONFIG_DRAM_START - The start address of installed DRAM + CONFIG_DRAM_START - The start address of installed DRAM - CONFIG_DRAM_START=0x20000000 + CONFIG_DRAM_START=0x20000000 - CONFIG_ARCH_IRQPRIO - The LM3S6918 supports interrupt prioritization + CONFIG_ARCH_IRQPRIO - The LM3S6918 supports interrupt prioritization - CONFIG_ARCH_IRQPRIO=y + CONFIG_ARCH_IRQPRIO=y - CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that - have LEDs + CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that + have LEDs - CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt - stack. If defined, this symbol is the size of the interrupt - stack in bytes. If not defined, the user task stacks will be - used during interrupt handling. + CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt + stack. If defined, this symbol is the size of the interrupt + stack in bytes. If not defined, the user task stacks will be + used during interrupt handling. - CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions + CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions - CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. + CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. - CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that - cause a 100 second delay during boot-up. This 100 second delay - serves no purpose other than it allows you to calibratre - CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure - the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until - the delay actually is 100 seconds. + CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that + cause a 100 second delay during boot-up. This 100 second delay + serves no purpose other than it allows you to calibratre + CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure + the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until + the delay actually is 100 seconds. There are configurations for disabling support for interrupts GPIO ports. GPIOH and GPIOJ must be disabled because they do not exist on the LM3S6432. Additional interrupt support can be disabled if desired to reduce memory footprint - GPIOs C-G are not pinned out on the MDL-S2E board. - CONFIG_LM3S_DISABLE_GPIOA_IRQS=n - CONFIG_LM3S_DISABLE_GPIOB_IRQS=n - CONFIG_LM3S_DISABLE_GPIOC_IRQS=y - CONFIG_LM3S_DISABLE_GPIOD_IRQS=y - CONFIG_LM3S_DISABLE_GPIOE_IRQS=y - CONFIG_LM3S_DISABLE_GPIOF_IRQS=y - CONFIG_LM3S_DISABLE_GPIOG_IRQS=y - CONFIG_LM3S_DISABLE_GPIOH_IRQS=y - CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y + CONFIG_LM3S_DISABLE_GPIOA_IRQS=n + CONFIG_LM3S_DISABLE_GPIOB_IRQS=n + CONFIG_LM3S_DISABLE_GPIOC_IRQS=y + CONFIG_LM3S_DISABLE_GPIOD_IRQS=y + CONFIG_LM3S_DISABLE_GPIOE_IRQS=y + CONFIG_LM3S_DISABLE_GPIOF_IRQS=y + CONFIG_LM3S_DISABLE_GPIOG_IRQS=y + CONFIG_LM3S_DISABLE_GPIOH_IRQS=y + CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y LM3S6432 specific device driver settings - CONFIG_UARTn_DISABLE - The TX and RX pins for UART1 share I/O pins with the TX and RX pins - for SSI0. To avoid conflicts, only one of SSI0 and UART1 should - be enabled in a configuration. - CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn for the - console and ttys0 (default is UART1). - CONFIG_UARTn_RXBUFSIZE - Characters are buffered as received. - This specific the size of the receive buffer - CONFIG_UARTn_TXBUFSIZE - Characters are buffered before - being sent. This specific the size of the transmit buffer - CONFIG_UARTn_BAUD - The configure BAUD of the UART. Must be - CONFIG_UARTn_BITS - The number of bits. Must be either 7 or 8. - CONFIG_UARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity - CONFIG_UARTn_2STOP - Two stop bits - - CONFIG_SSI0_DISABLE - Select to disable support for SSI0 - The TX and RX pins for SSI0 share I/O pins with the TX and RX pins - for UART1. To avoid conflicts, only one of SSI0 and UART1 should - be enabled in a configuration. - CONFIG_SSI1_DISABLE - Select to disable support for SSI1 - Note that the LM3S6432 only has one SSI, so SSI1 should always be - disabled. - CONFIG_SSI_POLLWAIT - Select to disable interrupt driven SSI support. - Poll-waiting is recommended if the interrupt rate would be to - high in the interrupt driven case. - CONFIG_SSI_TXLIMIT - Write this many words to the Tx FIFO before - emptying the Rx FIFO. If the SPI frequency is high and this - value is large, then larger values of this setting may cause - Rx FIFO overrun errors. Default: half of the Tx FIFO size (4). - - CONFIG_LM3S_ETHERNET - This must be set (along with CONFIG_NET) - to build the LM3S Ethernet driver - CONFIG_LM3S_ETHLEDS - Enable to use Ethernet LEDs on the board. - CONFIG_LM3S_BOARDMAC - This should be set in order to use the - MAC address configured in the flash USER registers. - CONFIG_LM3S_ETHHDUPLEX - Set to force half duplex operation - CONFIG_LM3S_ETHNOAUTOCRC - Set to suppress auto-CRC generation - CONFIG_LM3S_ETHNOPAD - Set to suppress Tx padding - CONFIG_LM3S_MULTICAST - Set to enable multicast frames - CONFIG_LM3S_PROMISCUOUS - Set to enable promiscuous mode - CONFIG_LM3S_BADCRC - Set to enable bad CRC rejection. - CONFIG_LM3S_DUMPPACKET - Dump each packet received/sent to the console. + CONFIG_UARTn_DISABLE + The TX and RX pins for UART1 share I/O pins with the TX and RX pins + for SSI0. To avoid conflicts, only one of SSI0 and UART1 should + be enabled in a configuration. + CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn for the + console and ttys0 (default is UART1). + CONFIG_UARTn_RXBUFSIZE - Characters are buffered as received. + This specific the size of the receive buffer + CONFIG_UARTn_TXBUFSIZE - Characters are buffered before + being sent. This specific the size of the transmit buffer + CONFIG_UARTn_BAUD - The configure BAUD of the UART. Must be + CONFIG_UARTn_BITS - The number of bits. Must be either 7 or 8. + CONFIG_UARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity + CONFIG_UARTn_2STOP - Two stop bits + + CONFIG_SSI0_DISABLE - Select to disable support for SSI0 + The TX and RX pins for SSI0 share I/O pins with the TX and RX pins + for UART1. To avoid conflicts, only one of SSI0 and UART1 should + be enabled in a configuration. + CONFIG_SSI1_DISABLE - Select to disable support for SSI1 + Note that the LM3S6432 only has one SSI, so SSI1 should always be + disabled. + CONFIG_SSI_POLLWAIT - Select to disable interrupt driven SSI support. + Poll-waiting is recommended if the interrupt rate would be to + high in the interrupt driven case. + CONFIG_SSI_TXLIMIT - Write this many words to the Tx FIFO before + emptying the Rx FIFO. If the SPI frequency is high and this + value is large, then larger values of this setting may cause + Rx FIFO overrun errors. Default: half of the Tx FIFO size (4). + + CONFIG_LM3S_ETHERNET - This must be set (along with CONFIG_NET) + to build the LM3S Ethernet driver + CONFIG_LM3S_ETHLEDS - Enable to use Ethernet LEDs on the board. + CONFIG_LM3S_BOARDMAC - This should be set in order to use the + MAC address configured in the flash USER registers. + CONFIG_LM3S_ETHHDUPLEX - Set to force half duplex operation + CONFIG_LM3S_ETHNOAUTOCRC - Set to suppress auto-CRC generation + CONFIG_LM3S_ETHNOPAD - Set to suppress Tx padding + CONFIG_LM3S_MULTICAST - Set to enable multicast frames + CONFIG_LM3S_PROMISCUOUS - Set to enable promiscuous mode + CONFIG_LM3S_BADCRC - Set to enable bad CRC rejection. + CONFIG_LM3S_DUMPPACKET - Dump each packet received/sent to the console. Configurations ^^^^^^^^^^^^^^ @@ -357,10 +406,10 @@ Configurations Each Stellaris MDL-S2E Reference Design configuration is maintained in a sudirectory and can be selected as follow: - cd tools - ./configure.sh lm3s6432-s2e/ - cd - - . ./setenv.sh + cd tools + ./configure.sh lm3s6432-s2e/ + cd - + . ./setenv.sh Where is one of the following: diff --git a/nuttx/configs/lm3s6965-ek/README.txt b/nuttx/configs/lm3s6965-ek/README.txt index fa0d1dad8..fc70b75fc 100644 --- a/nuttx/configs/lm3s6965-ek/README.txt +++ b/nuttx/configs/lm3s6965-ek/README.txt @@ -10,7 +10,9 @@ Contents Development Environment GNU Toolchain Options IDEs - NuttX buildroot Toolchain + NuttX EABI "buildroot" Toolchain + NuttX OABI "buildroot" Toolchain + NXFLAT Toolchain USB Device Controller Functions OLED Stellaris LM3S6965 Evaluation Kit Configuration Options @@ -210,8 +212,8 @@ IDEs Startup files will probably cause you some headaches. The NuttX startup file is arch/arm/src/lm3s/lm3s_vectors.S. -NuttX buildroot Toolchain -^^^^^^^^^^^^^^^^^^^^^^^^^ +NuttX EABI "buildroot" Toolchain +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ A GNU GCC-based toolchain is assumed. The files */setenv.sh should be modified to point to the correct path to the Cortex-M3 GCC toolchain (if @@ -234,7 +236,7 @@ NuttX buildroot Toolchain 4. cd /buildroot - 5. cp configs/cortexm3-defconfig-4.3.3 .config + 5. cp configs/cortexm3-eabi-defconfig-4.6.3 .config 6. make oldconfig @@ -244,11 +246,61 @@ NuttX buildroot Toolchain the path to the newly built binaries. See the file configs/README.txt in the buildroot source tree. That has more - detailed PLUS some special instructions that you will need to follow if you + details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. NOTE: This is an OABI toolchain. +NuttX OABI "buildroot" Toolchain +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + + The older, OABI buildroot toolchain is also available. To use the OABI + toolchain: + + 1. When building the buildroot toolchain, either (1) modify the cortexm3-eabi-defconfig-4.6.3 + configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI + configuration such as cortexm3-defconfig-4.3.3 + + 2. Modify the Make.defs file to use the OABI converntions: + + +CROSSDEV = arm-nuttx-elf- + +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + -CROSSDEV = arm-nuttx-eabi- + -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + +NXFLAT Toolchain +^^^^^^^^^^^^^^^^ + + If you are *not* using the NuttX buildroot toolchain and you want to use + the NXFLAT tools, then you will still have to build a portion of the buildroot + tools -- just the NXFLAT tools. The buildroot with the NXFLAT tools can + be downloaded from the NuttX SourceForge download site + (https://sourceforge.net/projects/nuttx/files/). + + This GNU toolchain builds and executes in the Linux or Cygwin environment. + + 1. You must have already configured Nuttx in /nuttx. + + cd tools + ./configure.sh lpcxpresso-lpc1768/ + + 2. Download the latest buildroot package into + + 3. unpack the buildroot tarball. The resulting directory may + have versioning information on it like buildroot-x.y.z. If so, + rename /buildroot-x.y.z to /buildroot. + + 4. cd /buildroot + + 5. cp configs/cortexm3-defconfig-nxflat .config + + 6. make oldconfig + + 7. make + + 8. Edit setenv.h, if necessary, so that the PATH variable includes + the path to the newly builtNXFLAT binaries. + USB Device Controller Functions ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ @@ -291,124 +343,124 @@ USB Device Controller Functions Stellaris LM3S6965 Evaluation Kit Configuration Options ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - CONFIG_ARCH - Identifies the arch/ subdirectory. This should - be set to: + CONFIG_ARCH - Identifies the arch/ subdirectory. This should + be set to: - CONFIG_ARCH=arm + CONFIG_ARCH=arm - CONFIG_ARCH_family - For use in C code: + CONFIG_ARCH_family - For use in C code: - CONFIG_ARCH_ARM=y + CONFIG_ARCH_ARM=y - CONFIG_ARCH_architecture - For use in C code: + CONFIG_ARCH_architecture - For use in C code: - CONFIG_ARCH_CORTEXM3=y + CONFIG_ARCH_CORTEXM3=y - CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory + CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory - CONFIG_ARCH_CHIP=lm3s + CONFIG_ARCH_CHIP=lm3s - CONFIG_ARCH_CHIP_name - For use in C code to identify the exact - chip: + CONFIG_ARCH_CHIP_name - For use in C code to identify the exact + chip: - CONFIG_ARCH_CHIP_LM3S6965 + CONFIG_ARCH_CHIP_LM3S6965 - CONFIG_ARCH_BOARD - Identifies the configs subdirectory and - hence, the board that supports the particular chip or SoC. + CONFIG_ARCH_BOARD - Identifies the configs subdirectory and + hence, the board that supports the particular chip or SoC. - CONFIG_ARCH_BOARD=lm3s6965-ek (for the Stellaris LM3S6965 Evaluation Kit) + CONFIG_ARCH_BOARD=lm3s6965-ek (for the Stellaris LM3S6965 Evaluation Kit) - CONFIG_ARCH_BOARD_name - For use in C code + CONFIG_ARCH_BOARD_name - For use in C code - CONFIG_ARCH_BOARD_LM3S6965EK + CONFIG_ARCH_BOARD_LM3S6965EK - CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation - of delay loops + CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation + of delay loops - CONFIG_ENDIAN_BIG - define if big endian (default is little - endian) + CONFIG_ENDIAN_BIG - define if big endian (default is little + endian) - CONFIG_DRAM_SIZE - Describes the installed DRAM (SRAM in this case): + CONFIG_DRAM_SIZE - Describes the installed DRAM (SRAM in this case): - CONFIG_DRAM_SIZE=0x00010000 (64Kb) + CONFIG_DRAM_SIZE=0x00010000 (64Kb) - CONFIG_DRAM_START - The start address of installed DRAM + CONFIG_DRAM_START - The start address of installed DRAM - CONFIG_DRAM_START=0x20000000 + CONFIG_DRAM_START=0x20000000 - CONFIG_ARCH_IRQPRIO - The LM3S6918 supports interrupt prioritization + CONFIG_ARCH_IRQPRIO - The LM3S6918 supports interrupt prioritization - CONFIG_ARCH_IRQPRIO=y + CONFIG_ARCH_IRQPRIO=y - CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that - have LEDs + CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that + have LEDs - CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt - stack. If defined, this symbol is the size of the interrupt - stack in bytes. If not defined, the user task stacks will be - used during interrupt handling. + CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt + stack. If defined, this symbol is the size of the interrupt + stack in bytes. If not defined, the user task stacks will be + used during interrupt handling. - CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions + CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions - CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. + CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. - CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that - cause a 100 second delay during boot-up. This 100 second delay - serves no purpose other than it allows you to calibratre - CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure - the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until - the delay actually is 100 seconds. + CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that + cause a 100 second delay during boot-up. This 100 second delay + serves no purpose other than it allows you to calibratre + CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure + the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until + the delay actually is 100 seconds. There are configurations for disabling support for interrupts GPIO ports. GPIOJ must be disabled because it does not exist on the LM3S6918. Additional interrupt support can be disabled if desired to reduce memory footprint. - CONFIG_LM3S_DISABLE_GPIOA_IRQS=n - CONFIG_LM3S_DISABLE_GPIOB_IRQS=n - CONFIG_LM3S_DISABLE_GPIOC_IRQS=n - CONFIG_LM3S_DISABLE_GPIOD_IRQS=n - CONFIG_LM3S_DISABLE_GPIOE_IRQS=n - CONFIG_LM3S_DISABLE_GPIOF_IRQS=n - CONFIG_LM3S_DISABLE_GPIOG_IRQS=n - CONFIG_LM3S_DISABLE_GPIOH_IRQS=n - CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y + CONFIG_LM3S_DISABLE_GPIOA_IRQS=n + CONFIG_LM3S_DISABLE_GPIOB_IRQS=n + CONFIG_LM3S_DISABLE_GPIOC_IRQS=n + CONFIG_LM3S_DISABLE_GPIOD_IRQS=n + CONFIG_LM3S_DISABLE_GPIOE_IRQS=n + CONFIG_LM3S_DISABLE_GPIOF_IRQS=n + CONFIG_LM3S_DISABLE_GPIOG_IRQS=n + CONFIG_LM3S_DISABLE_GPIOH_IRQS=n + CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y LM3S6818 specific device driver settings - CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn for the - console and ttys0 (default is the UART0). - CONFIG_UARTn_RXBUFSIZE - Characters are buffered as received. - This specific the size of the receive buffer - CONFIG_UARTn_TXBUFSIZE - Characters are buffered before - being sent. This specific the size of the transmit buffer - CONFIG_UARTn_BAUD - The configure BAUD of the UART. Must be - CONFIG_UARTn_BITS - The number of bits. Must be either 7 or 8. - CONFIG_UARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity - CONFIG_UARTn_2STOP - Two stop bits - - CONFIG_SSI0_DISABLE - Select to disable support for SSI0 - CONFIG_SSI1_DISABLE - Select to disable support for SSI1 - CONFIG_SSI_POLLWAIT - Select to disable interrupt driven SSI support. - Poll-waiting is recommended if the interrupt rate would be to - high in the interrupt driven case. - CONFIG_SSI_TXLIMIT - Write this many words to the Tx FIFO before - emptying the Rx FIFO. If the SPI frequency is high and this - value is large, then larger values of this setting may cause - Rx FIFO overrun errors. Default: half of the Tx FIFO size (4). - - CONFIG_LM3S_ETHERNET - This must be set (along with CONFIG_NET) - to build the LM3S Ethernet driver - CONFIG_LM3S_ETHLEDS - Enable to use Ethernet LEDs on the board. - CONFIG_LM3S_BOARDMAC - If the board-specific logic can provide - a MAC address (via lm3s_ethernetmac()), then this should be selected. - CONFIG_LM3S_ETHHDUPLEX - Set to force half duplex operation - CONFIG_LM3S_ETHNOAUTOCRC - Set to suppress auto-CRC generation - CONFIG_LM3S_ETHNOPAD - Set to suppress Tx padding - CONFIG_LM3S_MULTICAST - Set to enable multicast frames - CONFIG_LM3S_PROMISCUOUS - Set to enable promiscuous mode - CONFIG_LM3S_BADCRC - Set to enable bad CRC rejection. - CONFIG_LM3S_DUMPPACKET - Dump each packet received/sent to the console. + CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn for the + console and ttys0 (default is the UART0). + CONFIG_UARTn_RXBUFSIZE - Characters are buffered as received. + This specific the size of the receive buffer + CONFIG_UARTn_TXBUFSIZE - Characters are buffered before + being sent. This specific the size of the transmit buffer + CONFIG_UARTn_BAUD - The configure BAUD of the UART. Must be + CONFIG_UARTn_BITS - The number of bits. Must be either 7 or 8. + CONFIG_UARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity + CONFIG_UARTn_2STOP - Two stop bits + + CONFIG_SSI0_DISABLE - Select to disable support for SSI0 + CONFIG_SSI1_DISABLE - Select to disable support for SSI1 + CONFIG_SSI_POLLWAIT - Select to disable interrupt driven SSI support. + Poll-waiting is recommended if the interrupt rate would be to + high in the interrupt driven case. + CONFIG_SSI_TXLIMIT - Write this many words to the Tx FIFO before + emptying the Rx FIFO. If the SPI frequency is high and this + value is large, then larger values of this setting may cause + Rx FIFO overrun errors. Default: half of the Tx FIFO size (4). + + CONFIG_LM3S_ETHERNET - This must be set (along with CONFIG_NET) + to build the LM3S Ethernet driver + CONFIG_LM3S_ETHLEDS - Enable to use Ethernet LEDs on the board. + CONFIG_LM3S_BOARDMAC - If the board-specific logic can provide + a MAC address (via lm3s_ethernetmac()), then this should be selected. + CONFIG_LM3S_ETHHDUPLEX - Set to force half duplex operation + CONFIG_LM3S_ETHNOAUTOCRC - Set to suppress auto-CRC generation + CONFIG_LM3S_ETHNOPAD - Set to suppress Tx padding + CONFIG_LM3S_MULTICAST - Set to enable multicast frames + CONFIG_LM3S_PROMISCUOUS - Set to enable promiscuous mode + CONFIG_LM3S_BADCRC - Set to enable bad CRC rejection. + CONFIG_LM3S_DUMPPACKET - Dump each packet received/sent to the console. Configurations ^^^^^^^^^^^^^^ @@ -416,10 +468,10 @@ Configurations Each Stellaris LM3S6965 Evaluation Kit configuration is maintained in a sudirectory and can be selected as follow: - cd tools - ./configure.sh lm3s6965-ek/ - cd - - . ./setenv.sh + cd tools + ./configure.sh lm3s6965-ek/ + cd - + . ./setenv.sh Where is one of the following: diff --git a/nuttx/configs/lm3s8962-ek/README.txt b/nuttx/configs/lm3s8962-ek/README.txt index 6d6d17fee..043e5ceb3 100644 --- a/nuttx/configs/lm3s8962-ek/README.txt +++ b/nuttx/configs/lm3s8962-ek/README.txt @@ -10,7 +10,9 @@ Contents Development Environment GNU Toolchain Options IDEs - NuttX buildroot Toolchain + NuttX EABI "buildroot" Toolchain + NuttX OABI "buildroot" Toolchain + NXFLAT Toolchain USB Device Controller Functions OLED Stellaris LM3S8962 Evaluation Kit Configuration Options @@ -194,8 +196,8 @@ IDEs Startup files will probably cause you some headaches. The NuttX startup file is arch/arm/src/lm3s/lm3s_vectors.S. -NuttX buildroot Toolchain -^^^^^^^^^^^^^^^^^^^^^^^^^ +NuttX EABI "buildroot" Toolchain +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ A GNU GCC-based toolchain is assumed. The files */setenv.sh should be modified to point to the correct path to the Cortex-M3 GCC toolchain (if @@ -218,7 +220,7 @@ NuttX buildroot Toolchain 4. cd /buildroot - 5. cp configs/cortexm3-defconfig-4.3.3 .config + 5. cp configs/cortexm3-eabi-defconfig-4.6.3 .config 6. make oldconfig @@ -228,11 +230,61 @@ NuttX buildroot Toolchain the path to the newly built binaries. See the file configs/README.txt in the buildroot source tree. That has more - detailed PLUS some special instructions that you will need to follow if you + details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. NOTE: This is an OABI toolchain. +NuttX OABI "buildroot" Toolchain +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + + The older, OABI buildroot toolchain is also available. To use the OABI + toolchain: + + 1. When building the buildroot toolchain, either (1) modify the cortexm3-eabi-defconfig-4.6.3 + configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI + configuration such as cortexm3-defconfig-4.3.3 + + 2. Modify the Make.defs file to use the OABI converntions: + + +CROSSDEV = arm-nuttx-elf- + +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + -CROSSDEV = arm-nuttx-eabi- + -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + +NXFLAT Toolchain +^^^^^^^^^^^^^^^^ + + If you are *not* using the NuttX buildroot toolchain and you want to use + the NXFLAT tools, then you will still have to build a portion of the buildroot + tools -- just the NXFLAT tools. The buildroot with the NXFLAT tools can + be downloaded from the NuttX SourceForge download site + (https://sourceforge.net/projects/nuttx/files/). + + This GNU toolchain builds and executes in the Linux or Cygwin environment. + + 1. You must have already configured Nuttx in /nuttx. + + cd tools + ./configure.sh lpcxpresso-lpc1768/ + + 2. Download the latest buildroot package into + + 3. unpack the buildroot tarball. The resulting directory may + have versioning information on it like buildroot-x.y.z. If so, + rename /buildroot-x.y.z to /buildroot. + + 4. cd /buildroot + + 5. cp configs/cortexm3-defconfig-nxflat .config + + 6. make oldconfig + + 7. make + + 8. Edit setenv.h, if necessary, so that the PATH variable includes + the path to the newly builtNXFLAT binaries. + USB Device Controller Functions ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ @@ -275,124 +327,124 @@ USB Device Controller Functions Stellaris LM3S8962 Evaluation Kit Configuration Options ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - CONFIG_ARCH - Identifies the arch/ subdirectory. This should - be set to: + CONFIG_ARCH - Identifies the arch/ subdirectory. This should + be set to: - CONFIG_ARCH=arm + CONFIG_ARCH=arm - CONFIG_ARCH_family - For use in C code: + CONFIG_ARCH_family - For use in C code: - CONFIG_ARCH_ARM=y + CONFIG_ARCH_ARM=y - CONFIG_ARCH_architecture - For use in C code: + CONFIG_ARCH_architecture - For use in C code: - CONFIG_ARCH_CORTEXM3=y + CONFIG_ARCH_CORTEXM3=y - CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory + CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory - CONFIG_ARCH_CHIP=lm3s + CONFIG_ARCH_CHIP=lm3s - CONFIG_ARCH_CHIP_name - For use in C code to identify the exact - chip: + CONFIG_ARCH_CHIP_name - For use in C code to identify the exact + chip: - CONFIG_ARCH_CHIP_LM3S8962 + CONFIG_ARCH_CHIP_LM3S8962 - CONFIG_ARCH_BOARD - Identifies the configs subdirectory and - hence, the board that supports the particular chip or SoC. + CONFIG_ARCH_BOARD - Identifies the configs subdirectory and + hence, the board that supports the particular chip or SoC. - CONFIG_ARCH_BOARD=lm3s8962-ek (for the Stellaris LM3S8962 Evaluation Kit) + CONFIG_ARCH_BOARD=lm3s8962-ek (for the Stellaris LM3S8962 Evaluation Kit) - CONFIG_ARCH_BOARD_name - For use in C code + CONFIG_ARCH_BOARD_name - For use in C code - CONFIG_ARCH_BOARD_LM3S8962EK + CONFIG_ARCH_BOARD_LM3S8962EK - CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation - of delay loops + CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation + of delay loops - CONFIG_ENDIAN_BIG - define if big endian (default is little - endian) + CONFIG_ENDIAN_BIG - define if big endian (default is little + endian) - CONFIG_DRAM_SIZE - Describes the installed DRAM (SRAM in this case): + CONFIG_DRAM_SIZE - Describes the installed DRAM (SRAM in this case): - CONFIG_DRAM_SIZE=0x00010000 (64Kb) + CONFIG_DRAM_SIZE=0x00010000 (64Kb) - CONFIG_DRAM_START - The start address of installed DRAM + CONFIG_DRAM_START - The start address of installed DRAM - CONFIG_DRAM_START=0x20000000 + CONFIG_DRAM_START=0x20000000 - CONFIG_ARCH_IRQPRIO - The LM3S6918 supports interrupt prioritization + CONFIG_ARCH_IRQPRIO - The LM3S6918 supports interrupt prioritization - CONFIG_ARCH_IRQPRIO=y + CONFIG_ARCH_IRQPRIO=y - CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that - have LEDs + CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that + have LEDs - CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt - stack. If defined, this symbol is the size of the interrupt - stack in bytes. If not defined, the user task stacks will be - used during interrupt handling. + CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt + stack. If defined, this symbol is the size of the interrupt + stack in bytes. If not defined, the user task stacks will be + used during interrupt handling. - CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions + CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions - CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. + CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. - CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that - cause a 100 second delay during boot-up. This 100 second delay - serves no purpose other than it allows you to calibratre - CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure - the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until - the delay actually is 100 seconds. + CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that + cause a 100 second delay during boot-up. This 100 second delay + serves no purpose other than it allows you to calibratre + CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure + the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until + the delay actually is 100 seconds. There are configurations for disabling support for interrupts GPIO ports. GPIOJ must be disabled because it does not exist on the LM3S6918. Additional interrupt support can be disabled if desired to reduce memory footprint. - CONFIG_LM3S_DISABLE_GPIOA_IRQS=n - CONFIG_LM3S_DISABLE_GPIOB_IRQS=n - CONFIG_LM3S_DISABLE_GPIOC_IRQS=n - CONFIG_LM3S_DISABLE_GPIOD_IRQS=n - CONFIG_LM3S_DISABLE_GPIOE_IRQS=n - CONFIG_LM3S_DISABLE_GPIOF_IRQS=n - CONFIG_LM3S_DISABLE_GPIOG_IRQS=n - CONFIG_LM3S_DISABLE_GPIOH_IRQS=n - CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y + CONFIG_LM3S_DISABLE_GPIOA_IRQS=n + CONFIG_LM3S_DISABLE_GPIOB_IRQS=n + CONFIG_LM3S_DISABLE_GPIOC_IRQS=n + CONFIG_LM3S_DISABLE_GPIOD_IRQS=n + CONFIG_LM3S_DISABLE_GPIOE_IRQS=n + CONFIG_LM3S_DISABLE_GPIOF_IRQS=n + CONFIG_LM3S_DISABLE_GPIOG_IRQS=n + CONFIG_LM3S_DISABLE_GPIOH_IRQS=n + CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y LM3S6818 specific device driver settings - CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn for the - console and ttys0 (default is the UART0). - CONFIG_UARTn_RXBUFSIZE - Characters are buffered as received. - This specific the size of the receive buffer - CONFIG_UARTn_TXBUFSIZE - Characters are buffered before - being sent. This specific the size of the transmit buffer - CONFIG_UARTn_BAUD - The configure BAUD of the UART. Must be - CONFIG_UARTn_BITS - The number of bits. Must be either 7 or 8. - CONFIG_UARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity - CONFIG_UARTn_2STOP - Two stop bits - - CONFIG_SSI0_DISABLE - Select to disable support for SSI0 - CONFIG_SSI1_DISABLE - Select to disable support for SSI1 - CONFIG_SSI_POLLWAIT - Select to disable interrupt driven SSI support. - Poll-waiting is recommended if the interrupt rate would be to - high in the interrupt driven case. - CONFIG_SSI_TXLIMIT - Write this many words to the Tx FIFO before - emptying the Rx FIFO. If the SPI frequency is high and this - value is large, then larger values of this setting may cause - Rx FIFO overrun errors. Default: half of the Tx FIFO size (4). - - CONFIG_LM3S_ETHERNET - This must be set (along with CONFIG_NET) - to build the LM3S Ethernet driver - CONFIG_LM3S_ETHLEDS - Enable to use Ethernet LEDs on the board. - CONFIG_LM3S_BOARDMAC - If the board-specific logic can provide - a MAC address (via lm3s_ethernetmac()), then this should be selected. - CONFIG_LM3S_ETHHDUPLEX - Set to force half duplex operation - CONFIG_LM3S_ETHNOAUTOCRC - Set to suppress auto-CRC generation - CONFIG_LM3S_ETHNOPAD - Set to suppress Tx padding - CONFIG_LM3S_MULTICAST - Set to enable multicast frames - CONFIG_LM3S_PROMISCUOUS - Set to enable promiscuous mode - CONFIG_LM3S_BADCRC - Set to enable bad CRC rejection. - CONFIG_LM3S_DUMPPACKET - Dump each packet received/sent to the console. + CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn for the + console and ttys0 (default is the UART0). + CONFIG_UARTn_RXBUFSIZE - Characters are buffered as received. + This specific the size of the receive buffer + CONFIG_UARTn_TXBUFSIZE - Characters are buffered before + being sent. This specific the size of the transmit buffer + CONFIG_UARTn_BAUD - The configure BAUD of the UART. Must be + CONFIG_UARTn_BITS - The number of bits. Must be either 7 or 8. + CONFIG_UARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity + CONFIG_UARTn_2STOP - Two stop bits + + CONFIG_SSI0_DISABLE - Select to disable support for SSI0 + CONFIG_SSI1_DISABLE - Select to disable support for SSI1 + CONFIG_SSI_POLLWAIT - Select to disable interrupt driven SSI support. + Poll-waiting is recommended if the interrupt rate would be to + high in the interrupt driven case. + CONFIG_SSI_TXLIMIT - Write this many words to the Tx FIFO before + emptying the Rx FIFO. If the SPI frequency is high and this + value is large, then larger values of this setting may cause + Rx FIFO overrun errors. Default: half of the Tx FIFO size (4). + + CONFIG_LM3S_ETHERNET - This must be set (along with CONFIG_NET) + to build the LM3S Ethernet driver + CONFIG_LM3S_ETHLEDS - Enable to use Ethernet LEDs on the board. + CONFIG_LM3S_BOARDMAC - If the board-specific logic can provide + a MAC address (via lm3s_ethernetmac()), then this should be selected. + CONFIG_LM3S_ETHHDUPLEX - Set to force half duplex operation + CONFIG_LM3S_ETHNOAUTOCRC - Set to suppress auto-CRC generation + CONFIG_LM3S_ETHNOPAD - Set to suppress Tx padding + CONFIG_LM3S_MULTICAST - Set to enable multicast frames + CONFIG_LM3S_PROMISCUOUS - Set to enable promiscuous mode + CONFIG_LM3S_BADCRC - Set to enable bad CRC rejection. + CONFIG_LM3S_DUMPPACKET - Dump each packet received/sent to the console. Configurations ^^^^^^^^^^^^^^ @@ -400,10 +452,10 @@ Configurations Each Stellaris LM3S8962 Evaluation Kit configuration is maintained in a sudirectory and can be selected as follow: - cd tools - ./configure.sh lm3s8962-ek/ - cd - - . ./setenv.sh + cd tools + ./configure.sh lm3s8962-ek/ + cd - + . ./setenv.sh Where is one of the following: diff --git a/nuttx/configs/lpc4330-xplorer/README.txt b/nuttx/configs/lpc4330-xplorer/README.txt index 0d9ef87f2..a613edada 100644 --- a/nuttx/configs/lpc4330-xplorer/README.txt +++ b/nuttx/configs/lpc4330-xplorer/README.txt @@ -19,7 +19,9 @@ Contents Command Line Flash Programming Executing from SPIFI USB DFU Booting - - NuttX buildroot Toolchain + - NuttX EABI "buildroot" Toolchain + - NuttX OABI "buildroot" Toolchain + - NXFLAT Toolchain - Serial Console - FPU - LPC4330-Xplorer Configuration Options @@ -462,8 +464,8 @@ Code Red IDE/Tools To be provided. -NuttX buildroot Toolchain -========================= +NuttX EABI "buildroot" Toolchain +================================ A GNU GCC-based toolchain is assumed. The files */setenv.sh should be modified to point to the correct path to the Cortex-M3 GCC toolchain (if @@ -486,7 +488,7 @@ NuttX buildroot Toolchain 4. cd /buildroot - 5. cp configs/cortexm3-defconfig-4.3.3 .config + 5. cp configs/cortexm3-eabi-defconfig-4.6.3 .config 6. make oldconfig @@ -496,10 +498,58 @@ NuttX buildroot Toolchain the path to the newly built binaries. See the file configs/README.txt in the buildroot source tree. That has more - detailed PLUS some special instructions that you will need to follow if you + details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. - NOTE: This is an OABI toolchain. +NuttX OABI "buildroot" Toolchain +================================ + + The older, OABI buildroot toolchain is also available. To use the OABI + toolchain: + + 1. When building the buildroot toolchain, either (1) modify the cortexm3-eabi-defconfig-4.6.3 + configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI + configuration such as cortexm3-defconfig-4.3.3 + + 2. Modify the Make.defs file to use the OABI converntions: + + +CROSSDEV = arm-nuttx-elf- + +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + -CROSSDEV = arm-nuttx-eabi- + -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + +NXFLAT Toolchain +================ + + If you are *not* using the NuttX buildroot toolchain and you want to use + the NXFLAT tools, then you will still have to build a portion of the buildroot + tools -- just the NXFLAT tools. The buildroot with the NXFLAT tools can + be downloaded from the NuttX SourceForge download site + (https://sourceforge.net/projects/nuttx/files/). + + This GNU toolchain builds and executes in the Linux or Cygwin environment. + + 1. You must have already configured Nuttx in /nuttx. + + cd tools + ./configure.sh lpcxpresso-lpc1768/ + + 2. Download the latest buildroot package into + + 3. unpack the buildroot tarball. The resulting directory may + have versioning information on it like buildroot-x.y.z. If so, + rename /buildroot-x.y.z to /buildroot. + + 4. cd /buildroot + + 5. cp configs/cortexm3-defconfig-nxflat .config + + 6. make oldconfig + + 7. make + + 8. Edit setenv.h, if necessary, so that the PATH variable includes + the path to the newly builtNXFLAT binaries. Serial Console ============== diff --git a/nuttx/configs/lpcxpresso-lpc1768/README.txt b/nuttx/configs/lpcxpresso-lpc1768/README.txt index 402d52881..65f58d552 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/README.txt +++ b/nuttx/configs/lpcxpresso-lpc1768/README.txt @@ -11,7 +11,9 @@ Contents Embedded Artist's Base Board Development Environment GNU Toolchain Options - NuttX buildroot Toolchain + NuttX EABI "buildroot" Toolchain + NuttX OABI "buildroot" Toolchain + NXFLAT Toolchain Code Red IDE LEDs LPCXpresso Configuration Options @@ -406,8 +408,8 @@ Code Red IDE All of the above steps are automated in the bash script flash.sh that can be found in the configs/lpcxpresso/tools directory. -NuttX buildroot Toolchain -^^^^^^^^^^^^^^^^^^^^^^^^^ +NuttX EABI "buildroot" Toolchain +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ A GNU GCC-based toolchain is assumed. The files */setenv.sh should be modified to point to the correct path to the Cortex-M3 GCC toolchain (if @@ -430,7 +432,7 @@ NuttX buildroot Toolchain 4. cd /buildroot - 5. cp configs/cortexm3-defconfig-4.3.3 .config + 5. cp configs/cortexm3-eabi-defconfig-4.6.3 .config 6. make oldconfig @@ -440,10 +442,25 @@ NuttX buildroot Toolchain the path to the newly built binaries. See the file configs/README.txt in the buildroot source tree. That has more - detailed PLUS some special instructions that you will need to follow if you + details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. - NOTE: This is an OABI toolchain. +NuttX OABI "buildroot" Toolchain +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + + The older, OABI buildroot toolchain is also available. To use the OABI + toolchain: + + 1. When building the buildroot toolchain, either (1) modify the cortexm3-eabi-defconfig-4.6.3 + configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI + configuration such as cortexm3-defconfig-4.3.3 + + 2. Modify the Make.defs file to use the OABI converntions: + + +CROSSDEV = arm-nuttx-elf- + +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + -CROSSDEV = arm-nuttx-eabi- + -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft NXFLAT Toolchain ^^^^^^^^^^^^^^^^ diff --git a/nuttx/configs/mbed/README.txt b/nuttx/configs/mbed/README.txt index 2d53e7274..601c9a0b2 100644 --- a/nuttx/configs/mbed/README.txt +++ b/nuttx/configs/mbed/README.txt @@ -9,7 +9,9 @@ Contents Development Environment GNU Toolchain Options IDEs - NuttX buildroot Toolchain + NuttX EABI "buildroot" Toolchain + NuttX OABI "buildroot" Toolchain + NXFLAT Toolchain USB Device Controller Functions mbed Configuration Options USB Host Configuration @@ -120,8 +122,8 @@ IDEs Startup files will probably cause you some headaches. The NuttX startup file is arch/arm/src/lpc17x/lpc17_vectors.S. -NuttX buildroot Toolchain -^^^^^^^^^^^^^^^^^^^^^^^^^ +NuttX EABI "buildroot" Toolchain +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ A GNU GCC-based toolchain is assumed. The files */setenv.sh should be modified to point to the correct path to the Cortex-M3 GCC toolchain (if @@ -144,7 +146,7 @@ NuttX buildroot Toolchain 4. cd /buildroot - 5. cp configs/cortexm3-defconfig-4.3.3 .config + 5. cp configs/cortexm3-eabi-defconfig-4.6.3 .config 6. make oldconfig @@ -154,184 +156,232 @@ NuttX buildroot Toolchain the path to the newly built binaries. See the file configs/README.txt in the buildroot source tree. That has more - detailed PLUS some special instructions that you will need to follow if you + details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. - NOTE: This is an OABI toolchain. +NuttX OABI "buildroot" Toolchain +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + + The older, OABI buildroot toolchain is also available. To use the OABI + toolchain: + + 1. When building the buildroot toolchain, either (1) modify the cortexm3-eabi-defconfig-4.6.3 + configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI + configuration such as cortexm3-defconfig-4.3.3 + + 2. Modify the Make.defs file to use the OABI converntions: + + +CROSSDEV = arm-nuttx-elf- + +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + -CROSSDEV = arm-nuttx-eabi- + -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + +NXFLAT Toolchain +^^^^^^^^^^^^^^^^ + + If you are *not* using the NuttX buildroot toolchain and you want to use + the NXFLAT tools, then you will still have to build a portion of the buildroot + tools -- just the NXFLAT tools. The buildroot with the NXFLAT tools can + be downloaded from the NuttX SourceForge download site + (https://sourceforge.net/projects/nuttx/files/). + + This GNU toolchain builds and executes in the Linux or Cygwin environment. + + 1. You must have already configured Nuttx in /nuttx. + + cd tools + ./configure.sh lpcxpresso-lpc1768/ + + 2. Download the latest buildroot package into + + 3. unpack the buildroot tarball. The resulting directory may + have versioning information on it like buildroot-x.y.z. If so, + rename /buildroot-x.y.z to /buildroot. + + 4. cd /buildroot + + 5. cp configs/cortexm3-defconfig-nxflat .config + + 6. make oldconfig + + 7. make + + 8. Edit setenv.h, if necessary, so that the PATH variable includes + the path to the newly builtNXFLAT binaries. mbed Configuration Options ^^^^^^^^^^^^^^^^^^^^^^^^^^ - CONFIG_ARCH - Identifies the arch/ subdirectory. This should - be set to: + CONFIG_ARCH - Identifies the arch/ subdirectory. This should + be set to: - CONFIG_ARCH=arm + CONFIG_ARCH=arm - CONFIG_ARCH_family - For use in C code: + CONFIG_ARCH_family - For use in C code: - CONFIG_ARCH_ARM=y + CONFIG_ARCH_ARM=y - CONFIG_ARCH_architecture - For use in C code: + CONFIG_ARCH_architecture - For use in C code: - CONFIG_ARCH_CORTEXM3=y + CONFIG_ARCH_CORTEXM3=y - CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory + CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory - CONFIG_ARCH_CHIP=lpc17xx + CONFIG_ARCH_CHIP=lpc17xx - CONFIG_ARCH_CHIP_name - For use in C code to identify the exact - chip: + CONFIG_ARCH_CHIP_name - For use in C code to identify the exact + chip: - CONFIG_ARCH_CHIP_LPC1768=y + CONFIG_ARCH_CHIP_LPC1768=y - CONFIG_ARCH_BOARD - Identifies the configs subdirectory and - hence, the board that supports the particular chip or SoC. + CONFIG_ARCH_BOARD - Identifies the configs subdirectory and + hence, the board that supports the particular chip or SoC. - CONFIG_ARCH_BOARD=mbed (for the mbed.org board) + CONFIG_ARCH_BOARD=mbed (for the mbed.org board) - CONFIG_ARCH_BOARD_name - For use in C code + CONFIG_ARCH_BOARD_name - For use in C code - CONFIG_ARCH_BOARD_MBED=y + CONFIG_ARCH_BOARD_MBED=y - CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation - of delay loops + CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation + of delay loops - CONFIG_ENDIAN_BIG - define if big endian (default is little - endian) + CONFIG_ENDIAN_BIG - define if big endian (default is little + endian) - CONFIG_DRAM_SIZE - Describes the installed DRAM (CPU SRAM in this case): + CONFIG_DRAM_SIZE - Describes the installed DRAM (CPU SRAM in this case): - CONFIG_DRAM_SIZE=(32*1024) (32Kb) + CONFIG_DRAM_SIZE=(32*1024) (32Kb) - There is an additional 32Kb of SRAM in AHB SRAM banks 0 and 1. + There is an additional 32Kb of SRAM in AHB SRAM banks 0 and 1. - CONFIG_DRAM_START - The start address of installed DRAM + CONFIG_DRAM_START - The start address of installed DRAM - CONFIG_DRAM_START=0x10000000 + CONFIG_DRAM_START=0x10000000 - CONFIG_ARCH_IRQPRIO - The LPC17xx supports interrupt prioritization + CONFIG_ARCH_IRQPRIO - The LPC17xx supports interrupt prioritization - CONFIG_ARCH_IRQPRIO=y + CONFIG_ARCH_IRQPRIO=y - CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that - have LEDs + CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that + have LEDs - CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt - stack. If defined, this symbol is the size of the interrupt - stack in bytes. If not defined, the user task stacks will be - used during interrupt handling. + CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt + stack. If defined, this symbol is the size of the interrupt + stack in bytes. If not defined, the user task stacks will be + used during interrupt handling. - CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions + CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions - CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. + CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. - CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that - cause a 100 second delay during boot-up. This 100 second delay - serves no purpose other than it allows you to calibratre - CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure - the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until - the delay actually is 100 seconds. + CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that + cause a 100 second delay during boot-up. This 100 second delay + serves no purpose other than it allows you to calibratre + CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure + the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until + the delay actually is 100 seconds. - Individual subsystems can be enabled: - CONFIG_LPC17_MAINOSC=y - CONFIG_LPC17_PLL0=y - CONFIG_LPC17_PLL1=n - CONFIG_LPC17_ETHERNET=n - CONFIG_LPC17_USBHOST=n - CONFIG_LPC17_USBOTG=n - CONFIG_LPC17_USBDEV=n - CONFIG_LPC17_UART0=y - CONFIG_LPC17_UART1=n - CONFIG_LPC17_UART2=n - CONFIG_LPC17_UART3=n - CONFIG_LPC17_CAN1=n - CONFIG_LPC17_CAN2=n - CONFIG_LPC17_SPI=n - CONFIG_LPC17_SSP0=n - CONFIG_LPC17_SSP1=n - CONFIG_LPC17_I2C0=n - CONFIG_LPC17_I2C1=n - CONFIG_LPC17_I2S=n - CONFIG_LPC17_TMR0=n - CONFIG_LPC17_TMR1=n - CONFIG_LPC17_TMR2=n - CONFIG_LPC17_TMR3=n - CONFIG_LPC17_RIT=n - CONFIG_LPC17_PWM=n - CONFIG_LPC17_MCPWM=n - CONFIG_LPC17_QEI=n - CONFIG_LPC17_RTC=n - CONFIG_LPC17_WDT=n - CONFIG_LPC17_ADC=n - CONFIG_LPC17_DAC=n - CONFIG_LPC17_GPDMA=n - CONFIG_LPC17_FLASH=n + Individual subsystems can be enabled: + CONFIG_LPC17_MAINOSC=y + CONFIG_LPC17_PLL0=y + CONFIG_LPC17_PLL1=n + CONFIG_LPC17_ETHERNET=n + CONFIG_LPC17_USBHOST=n + CONFIG_LPC17_USBOTG=n + CONFIG_LPC17_USBDEV=n + CONFIG_LPC17_UART0=y + CONFIG_LPC17_UART1=n + CONFIG_LPC17_UART2=n + CONFIG_LPC17_UART3=n + CONFIG_LPC17_CAN1=n + CONFIG_LPC17_CAN2=n + CONFIG_LPC17_SPI=n + CONFIG_LPC17_SSP0=n + CONFIG_LPC17_SSP1=n + CONFIG_LPC17_I2C0=n + CONFIG_LPC17_I2C1=n + CONFIG_LPC17_I2S=n + CONFIG_LPC17_TMR0=n + CONFIG_LPC17_TMR1=n + CONFIG_LPC17_TMR2=n + CONFIG_LPC17_TMR3=n + CONFIG_LPC17_RIT=n + CONFIG_LPC17_PWM=n + CONFIG_LPC17_MCPWM=n + CONFIG_LPC17_QEI=n + CONFIG_LPC17_RTC=n + CONFIG_LPC17_WDT=n + CONFIG_LPC17_ADC=n + CONFIG_LPC17_DAC=n + CONFIG_LPC17_GPDMA=n + CONFIG_LPC17_FLASH=n LPC17xx specific device driver settings - CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn for the - console and ttys0 (default is the UART0). - CONFIG_UARTn_RXBUFSIZE - Characters are buffered as received. - This specific the size of the receive buffer - CONFIG_UARTn_TXBUFSIZE - Characters are buffered before - being sent. This specific the size of the transmit buffer - CONFIG_UARTn_BAUD - The configure BAUD of the UART. Must be - CONFIG_UARTn_BITS - The number of bits. Must be either 7 or 8. - CONFIG_UARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity - CONFIG_UARTn_2STOP - Two stop bits + CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn for the + console and ttys0 (default is the UART0). + CONFIG_UARTn_RXBUFSIZE - Characters are buffered as received. + This specific the size of the receive buffer + CONFIG_UARTn_TXBUFSIZE - Characters are buffered before + being sent. This specific the size of the transmit buffer + CONFIG_UARTn_BAUD - The configure BAUD of the UART. Must be + CONFIG_UARTn_BITS - The number of bits. Must be either 7 or 8. + CONFIG_UARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity + CONFIG_UARTn_2STOP - Two stop bits LPC17xx specific CAN device driver settings. These settings all require CONFIG_CAN: - CONFIG_CAN_EXTID - Enables support for the 29-bit extended ID. Default - Standard 11-bit IDs. - CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN1 is defined. - CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN2 is defined. - CONFIG_CAN1_DIVISOR - CAN1 is clocked at CCLK divided by this number. - (the CCLK frequency is divided by this number to get the CAN clock). - Options = {1,2,4,6}. Default: 4. - CONFIG_CAN2_DIVISOR - CAN2 is clocked at CCLK divided by this number. - (the CCLK frequency is divided by this number to get the CAN clock). - Options = {1,2,4,6}. Default: 4. - CONFIG_CAN_TSEG1 - The number of CAN time quanta in segment 1. Default: 6 - CONFIG_CAN_TSEG2 = the number of CAN time quanta in segment 2. Default: 7 + CONFIG_CAN_EXTID - Enables support for the 29-bit extended ID. Default + Standard 11-bit IDs. + CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN1 is defined. + CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN2 is defined. + CONFIG_CAN1_DIVISOR - CAN1 is clocked at CCLK divided by this number. + (the CCLK frequency is divided by this number to get the CAN clock). + Options = {1,2,4,6}. Default: 4. + CONFIG_CAN2_DIVISOR - CAN2 is clocked at CCLK divided by this number. + (the CCLK frequency is divided by this number to get the CAN clock). + Options = {1,2,4,6}. Default: 4. + CONFIG_CAN_TSEG1 - The number of CAN time quanta in segment 1. Default: 6 + CONFIG_CAN_TSEG2 = the number of CAN time quanta in segment 2. Default: 7 LPC17xx specific PHY/Ethernet device driver settings. These setting also require CONFIG_NET and CONFIG_LPC17_ETHERNET. - CONFIG_PHY_KS8721 - Selects Micrel KS8721 PHY - CONFIG_PHY_AUTONEG - Enable auto-negotion - CONFIG_PHY_SPEED100 - Select 100Mbit vs. 10Mbit speed. - CONFIG_PHY_FDUPLEX - Select full (vs. half) duplex + CONFIG_PHY_KS8721 - Selects Micrel KS8721 PHY + CONFIG_PHY_AUTONEG - Enable auto-negotion + CONFIG_PHY_SPEED100 - Select 100Mbit vs. 10Mbit speed. + CONFIG_PHY_FDUPLEX - Select full (vs. half) duplex CONFIG_NET_EMACRAM_SIZE - Size of EMAC RAM. Default: 16Kb - CONFIG_NET_NTXDESC - Configured number of Tx descriptors. Default: 18 - CONFIG_NET_NRXDESC - Configured number of Rx descriptors. Default: 18 - CONFIG_NET_PRIORITY - Ethernet interrupt priority. The is default is - the higest priority. - CONFIG_NET_WOL - Enable Wake-up on Lan (not fully implemented). - CONFIG_NET_REGDEBUG - Enabled low level register debug. Also needs - CONFIG_DEBUG. - CONFIG_NET_DUMPPACKET - Dump all received and transmitted packets. - Also needs CONFIG_DEBUG. - CONFIG_NET_HASH - Enable receipt of near-perfect match frames. - CONFIG_NET_MULTICAST - Enable receipt of multicast (and unicast) frames. + CONFIG_NET_NTXDESC - Configured number of Tx descriptors. Default: 18 + CONFIG_NET_NRXDESC - Configured number of Rx descriptors. Default: 18 + CONFIG_NET_PRIORITY - Ethernet interrupt priority. The is default is + the higest priority. + CONFIG_NET_WOL - Enable Wake-up on Lan (not fully implemented). + CONFIG_NET_REGDEBUG - Enabled low level register debug. Also needs + CONFIG_DEBUG. + CONFIG_NET_DUMPPACKET - Dump all received and transmitted packets. + Also needs CONFIG_DEBUG. + CONFIG_NET_HASH - Enable receipt of near-perfect match frames. + CONFIG_NET_MULTICAST - Enable receipt of multicast (and unicast) frames. Automatically set if CONFIG_NET_IGMP is selected. LPC17xx USB Device Configuration - CONFIG_LPC17_USBDEV_FRAME_INTERRUPT - Handle USB Start-Of-Frame events. - Enable reading SOF from interrupt handler vs. simply reading on demand. - Probably a bad idea... Unless there is some issue with sampling the SOF - from hardware asynchronously. - CONFIG_LPC17_USBDEV_EPFAST_INTERRUPT - Enable high priority interrupts. I have no idea why you might want to - do that - CONFIG_LPC17_USBDEV_NDMADESCRIPTORS - Number of DMA descriptors to allocate in SRAM. - CONFIG_LPC17_USBDEV_DMA - Enable lpc17xx-specific DMA support + CONFIG_LPC17_USBDEV_FRAME_INTERRUPT + Handle USB Start-Of-Frame events. + Enable reading SOF from interrupt handler vs. simply reading on demand. + Probably a bad idea... Unless there is some issue with sampling the SOF + from hardware asynchronously. + CONFIG_LPC17_USBDEV_EPFAST_INTERRUPT + Enable high priority interrupts. I have no idea why you might want to + do that + CONFIG_LPC17_USBDEV_NDMADESCRIPTORS + Number of DMA descriptors to allocate in SRAM. + CONFIG_LPC17_USBDEV_DMA + Enable lpc17xx-specific DMA support CONFIG_LPC17_USBDEV_NOVBUS Define if the hardware implementation does not support the VBUS signal CONFIG_LPC17_USBDEV_NOLED @@ -396,10 +446,10 @@ Configurations Each mbed configuration is maintained in a sudirectory and can be selected as follow: - cd tools - ./configure.sh mbed/ - cd - - . ./setenv.sh + cd tools + ./configure.sh mbed/ + cd - + . ./setenv.sh Where is one of the following: diff --git a/nuttx/configs/mcu123-lpc214x/README.txt b/nuttx/configs/mcu123-lpc214x/README.txt index b819abf36..65d177cc1 100644 --- a/nuttx/configs/mcu123-lpc214x/README.txt +++ b/nuttx/configs/mcu123-lpc214x/README.txt @@ -113,7 +113,7 @@ NuttX buildroot Toolchain 4. cd /buildroot - 5. cp configs/cortexm3-defconfig-4.3.3 .config + 5. cp configs/arm7tdmi-defconfig-4.3.3 .config 6. make oldconfig diff --git a/nuttx/configs/nucleus2g/README.txt b/nuttx/configs/nucleus2g/README.txt index e2389339e..01b6adef7 100644 --- a/nuttx/configs/nucleus2g/README.txt +++ b/nuttx/configs/nucleus2g/README.txt @@ -11,7 +11,9 @@ Contents Development Environment GNU Toolchain Options IDEs - NuttX buildroot Toolchain + NuttX EABI "buildroot" Toolchain + NuttX OABI "buildroot" Toolchain + NXFLAT Toolchain LEDs Nucleus 2G Configuration Options Configurations @@ -180,8 +182,8 @@ IDEs Startup files will probably cause you some headaches. The NuttX startup file is arch/arm/src/lpc17x/lpc17_vectors.S. -NuttX buildroot Toolchain -^^^^^^^^^^^^^^^^^^^^^^^^^ +NuttX EABI "buildroot" Toolchain +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ A GNU GCC-based toolchain is assumed. The files */setenv.sh should be modified to point to the correct path to the Cortex-M3 GCC toolchain (if @@ -204,7 +206,7 @@ NuttX buildroot Toolchain 4. cd /buildroot - 5. cp configs/cortexm3-defconfig-4.3.3 .config + 5. cp configs/cortexm3-eabi-defconfig-4.6.3 .config 6. make oldconfig @@ -214,10 +216,58 @@ NuttX buildroot Toolchain the path to the newly built binaries. See the file configs/README.txt in the buildroot source tree. That has more - detailed PLUS some special instructions that you will need to follow if you + details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. - NOTE: This is an OABI toolchain. +NuttX OABI "buildroot" Toolchain +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + + The older, OABI buildroot toolchain is also available. To use the OABI + toolchain: + + 1. When building the buildroot toolchain, either (1) modify the cortexm3-eabi-defconfig-4.6.3 + configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI + configuration such as cortexm3-defconfig-4.3.3 + + 2. Modify the Make.defs file to use the OABI converntions: + + +CROSSDEV = arm-nuttx-elf- + +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + -CROSSDEV = arm-nuttx-eabi- + -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + +NXFLAT Toolchain +^^^^^^^^^^^^^^^^ + + If you are *not* using the NuttX buildroot toolchain and you want to use + the NXFLAT tools, then you will still have to build a portion of the buildroot + tools -- just the NXFLAT tools. The buildroot with the NXFLAT tools can + be downloaded from the NuttX SourceForge download site + (https://sourceforge.net/projects/nuttx/files/). + + This GNU toolchain builds and executes in the Linux or Cygwin environment. + + 1. You must have already configured Nuttx in /nuttx. + + cd tools + ./configure.sh lpcxpresso-lpc1768/ + + 2. Download the latest buildroot package into + + 3. unpack the buildroot tarball. The resulting directory may + have versioning information on it like buildroot-x.y.z. If so, + rename /buildroot-x.y.z to /buildroot. + + 4. cd /buildroot + + 5. cp configs/cortexm3-defconfig-nxflat .config + + 6. make oldconfig + + 7. make + + 8. Edit setenv.h, if necessary, so that the PATH variable includes + the path to the newly builtNXFLAT binaries. LEDs ^^^^ @@ -274,176 +324,176 @@ LEDs Nucleus 2G Configuration Options ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - CONFIG_ARCH - Identifies the arch/ subdirectory. This should - be set to: + CONFIG_ARCH - Identifies the arch/ subdirectory. This should + be set to: - CONFIG_ARCH=arm + CONFIG_ARCH=arm - CONFIG_ARCH_family - For use in C code: + CONFIG_ARCH_family - For use in C code: - CONFIG_ARCH_ARM=y + CONFIG_ARCH_ARM=y - CONFIG_ARCH_architecture - For use in C code: + CONFIG_ARCH_architecture - For use in C code: - CONFIG_ARCH_CORTEXM3=y + CONFIG_ARCH_CORTEXM3=y - CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory + CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory - CONFIG_ARCH_CHIP=lpc17xx + CONFIG_ARCH_CHIP=lpc17xx - CONFIG_ARCH_CHIP_name - For use in C code to identify the exact - chip: + CONFIG_ARCH_CHIP_name - For use in C code to identify the exact + chip: - CONFIG_ARCH_CHIP_LPC1768=y + CONFIG_ARCH_CHIP_LPC1768=y - CONFIG_ARCH_BOARD - Identifies the configs subdirectory and - hence, the board that supports the particular chip or SoC. + CONFIG_ARCH_BOARD - Identifies the configs subdirectory and + hence, the board that supports the particular chip or SoC. - CONFIG_ARCH_BOARD=nucleus2g (for the Nucleus 2G) + CONFIG_ARCH_BOARD=nucleus2g (for the Nucleus 2G) - CONFIG_ARCH_BOARD_name - For use in C code + CONFIG_ARCH_BOARD_name - For use in C code - CONFIG_ARCH_BOARD_NUCLEUS2G=y + CONFIG_ARCH_BOARD_NUCLEUS2G=y - CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation - of delay loops + CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation + of delay loops - CONFIG_ENDIAN_BIG - define if big endian (default is little - endian) + CONFIG_ENDIAN_BIG - define if big endian (default is little + endian) - CONFIG_DRAM_SIZE - Describes the installed DRAM (CPU SRAM in this case): + CONFIG_DRAM_SIZE - Describes the installed DRAM (CPU SRAM in this case): - CONFIG_DRAM_SIZE=(32*1024) (32Kb) + CONFIG_DRAM_SIZE=(32*1024) (32Kb) - There is an additional 32Kb of SRAM in AHB SRAM banks 0 and 1. + There is an additional 32Kb of SRAM in AHB SRAM banks 0 and 1. - CONFIG_DRAM_START - The start address of installed DRAM + CONFIG_DRAM_START - The start address of installed DRAM - CONFIG_DRAM_START=0x10000000 + CONFIG_DRAM_START=0x10000000 - CONFIG_ARCH_IRQPRIO - The LPC17xx supports interrupt prioritization + CONFIG_ARCH_IRQPRIO - The LPC17xx supports interrupt prioritization - CONFIG_ARCH_IRQPRIO=y + CONFIG_ARCH_IRQPRIO=y - CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that - have LEDs + CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that + have LEDs - CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt - stack. If defined, this symbol is the size of the interrupt - stack in bytes. If not defined, the user task stacks will be - used during interrupt handling. + CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt + stack. If defined, this symbol is the size of the interrupt + stack in bytes. If not defined, the user task stacks will be + used during interrupt handling. - CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions + CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions - CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. + CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. - CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that - cause a 100 second delay during boot-up. This 100 second delay - serves no purpose other than it allows you to calibratre - CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure - the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until - the delay actually is 100 seconds. + CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that + cause a 100 second delay during boot-up. This 100 second delay + serves no purpose other than it allows you to calibratre + CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure + the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until + the delay actually is 100 seconds. - Individual subsystems can be enabled: - CONFIG_LPC17_MAINOSC=y - CONFIG_LPC17_PLL0=y - CONFIG_LPC17_PLL1=n - CONFIG_LPC17_ETHERNET=n - CONFIG_LPC17_USBHOST=n - CONFIG_LPC17_USBOTG=n - CONFIG_LPC17_USBDEV=n - CONFIG_LPC17_UART0=y - CONFIG_LPC17_UART1=n - CONFIG_LPC17_UART2=n - CONFIG_LPC17_UART3=n - CONFIG_LPC17_CAN1=n - CONFIG_LPC17_CAN2=n - CONFIG_LPC17_SPI=n - CONFIG_LPC17_SSP0=n - CONFIG_LPC17_SSP1=n - CONFIG_LPC17_I2C0=n - CONFIG_LPC17_I2C1=n - CONFIG_LPC17_I2S=n - CONFIG_LPC17_TMR0=n - CONFIG_LPC17_TMR1=n - CONFIG_LPC17_TMR2=n - CONFIG_LPC17_TMR3=n - CONFIG_LPC17_RIT=n - CONFIG_LPC17_PWM=n - CONFIG_LPC17_MCPWM=n - CONFIG_LPC17_QEI=n - CONFIG_LPC17_RTC=n - CONFIG_LPC17_WDT=n - CONFIG_LPC17_ADC=n - CONFIG_LPC17_DAC=n - CONFIG_LPC17_GPDMA=n - CONFIG_LPC17_FLASH=n + Individual subsystems can be enabled: + CONFIG_LPC17_MAINOSC=y + CONFIG_LPC17_PLL0=y + CONFIG_LPC17_PLL1=n + CONFIG_LPC17_ETHERNET=n + CONFIG_LPC17_USBHOST=n + CONFIG_LPC17_USBOTG=n + CONFIG_LPC17_USBDEV=n + CONFIG_LPC17_UART0=y + CONFIG_LPC17_UART1=n + CONFIG_LPC17_UART2=n + CONFIG_LPC17_UART3=n + CONFIG_LPC17_CAN1=n + CONFIG_LPC17_CAN2=n + CONFIG_LPC17_SPI=n + CONFIG_LPC17_SSP0=n + CONFIG_LPC17_SSP1=n + CONFIG_LPC17_I2C0=n + CONFIG_LPC17_I2C1=n + CONFIG_LPC17_I2S=n + CONFIG_LPC17_TMR0=n + CONFIG_LPC17_TMR1=n + CONFIG_LPC17_TMR2=n + CONFIG_LPC17_TMR3=n + CONFIG_LPC17_RIT=n + CONFIG_LPC17_PWM=n + CONFIG_LPC17_MCPWM=n + CONFIG_LPC17_QEI=n + CONFIG_LPC17_RTC=n + CONFIG_LPC17_WDT=n + CONFIG_LPC17_ADC=n + CONFIG_LPC17_DAC=n + CONFIG_LPC17_GPDMA=n + CONFIG_LPC17_FLASH=n LPC17xx specific device driver settings - CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn for the - console and ttys0 (default is the UART0). - CONFIG_UARTn_RXBUFSIZE - Characters are buffered as received. - This specific the size of the receive buffer - CONFIG_UARTn_TXBUFSIZE - Characters are buffered before - being sent. This specific the size of the transmit buffer - CONFIG_UARTn_BAUD - The configure BAUD of the UART. Must be - CONFIG_UARTn_BITS - The number of bits. Must be either 7 or 8. - CONFIG_UARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity - CONFIG_UARTn_2STOP - Two stop bits + CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn for the + console and ttys0 (default is the UART0). + CONFIG_UARTn_RXBUFSIZE - Characters are buffered as received. + This specific the size of the receive buffer + CONFIG_UARTn_TXBUFSIZE - Characters are buffered before + being sent. This specific the size of the transmit buffer + CONFIG_UARTn_BAUD - The configure BAUD of the UART. Must be + CONFIG_UARTn_BITS - The number of bits. Must be either 7 or 8. + CONFIG_UARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity + CONFIG_UARTn_2STOP - Two stop bits LPC17xx specific CAN device driver settings. These settings all require CONFIG_CAN: - CONFIG_CAN_EXTID - Enables support for the 29-bit extended ID. Default - Standard 11-bit IDs. - CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN1 is defined. - CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN2 is defined. - CONFIG_CAN1_DIVISOR - CAN1 is clocked at CCLK divided by this number. - (the CCLK frequency is divided by this number to get the CAN clock). - Options = {1,2,4,6}. Default: 4. - CONFIG_CAN2_DIVISOR - CAN2 is clocked at CCLK divided by this number. - (the CCLK frequency is divided by this number to get the CAN clock). - Options = {1,2,4,6}. Default: 4. - CONFIG_CAN_TSEG1 - The number of CAN time quanta in segment 1. Default: 6 - CONFIG_CAN_TSEG2 = the number of CAN time quanta in segment 2. Default: 7 + CONFIG_CAN_EXTID - Enables support for the 29-bit extended ID. Default + Standard 11-bit IDs. + CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN1 is defined. + CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN2 is defined. + CONFIG_CAN1_DIVISOR - CAN1 is clocked at CCLK divided by this number. + (the CCLK frequency is divided by this number to get the CAN clock). + Options = {1,2,4,6}. Default: 4. + CONFIG_CAN2_DIVISOR - CAN2 is clocked at CCLK divided by this number. + (the CCLK frequency is divided by this number to get the CAN clock). + Options = {1,2,4,6}. Default: 4. + CONFIG_CAN_TSEG1 - The number of CAN time quanta in segment 1. Default: 6 + CONFIG_CAN_TSEG2 = the number of CAN time quanta in segment 2. Default: 7 LPC17xx specific PHY/Ethernet device driver settings. These setting also require CONFIG_NET and CONFIG_LPC17_ETHERNET. - CONFIG_PHY_KS8721 - Selects Micrel KS8721 PHY - CONFIG_PHY_AUTONEG - Enable auto-negotion - CONFIG_PHY_SPEED100 - Select 100Mbit vs. 10Mbit speed. - CONFIG_PHY_FDUPLEX - Select full (vs. half) duplex + CONFIG_PHY_KS8721 - Selects Micrel KS8721 PHY + CONFIG_PHY_AUTONEG - Enable auto-negotion + CONFIG_PHY_SPEED100 - Select 100Mbit vs. 10Mbit speed. + CONFIG_PHY_FDUPLEX - Select full (vs. half) duplex CONFIG_NET_EMACRAM_SIZE - Size of EMAC RAM. Default: 16Kb - CONFIG_NET_NTXDESC - Configured number of Tx descriptors. Default: 18 - CONFIG_NET_NRXDESC - Configured number of Rx descriptors. Default: 18 - CONFIG_NET_PRIORITY - Ethernet interrupt priority. The is default is - the higest priority. - CONFIG_NET_WOL - Enable Wake-up on Lan (not fully implemented). - CONFIG_NET_REGDEBUG - Enabled low level register debug. Also needs - CONFIG_DEBUG. - CONFIG_NET_DUMPPACKET - Dump all received and transmitted packets. - Also needs CONFIG_DEBUG. - CONFIG_NET_HASH - Enable receipt of near-perfect match frames. - CONFIG_NET_MULTICAST - Enable receipt of multicast (and unicast) frames. + CONFIG_NET_NTXDESC - Configured number of Tx descriptors. Default: 18 + CONFIG_NET_NRXDESC - Configured number of Rx descriptors. Default: 18 + CONFIG_NET_PRIORITY - Ethernet interrupt priority. The is default is + the higest priority. + CONFIG_NET_WOL - Enable Wake-up on Lan (not fully implemented). + CONFIG_NET_REGDEBUG - Enabled low level register debug. Also needs + CONFIG_DEBUG. + CONFIG_NET_DUMPPACKET - Dump all received and transmitted packets. + Also needs CONFIG_DEBUG. + CONFIG_NET_HASH - Enable receipt of near-perfect match frames. + CONFIG_NET_MULTICAST - Enable receipt of multicast (and unicast) frames. Automatically set if CONFIG_NET_IGMP is selected. LPC17xx USB Device Configuration - CONFIG_LPC17_USBDEV_FRAME_INTERRUPT - Handle USB Start-Of-Frame events. - Enable reading SOF from interrupt handler vs. simply reading on demand. - Probably a bad idea... Unless there is some issue with sampling the SOF - from hardware asynchronously. - CONFIG_LPC17_USBDEV_EPFAST_INTERRUPT - Enable high priority interrupts. I have no idea why you might want to - do that - CONFIG_LPC17_USBDEV_NDMADESCRIPTORS - Number of DMA descriptors to allocate in SRAM. - CONFIG_LPC17_USBDEV_DMA - Enable lpc17xx-specific DMA support + CONFIG_LPC17_USBDEV_FRAME_INTERRUPT + Handle USB Start-Of-Frame events. + Enable reading SOF from interrupt handler vs. simply reading on demand. + Probably a bad idea... Unless there is some issue with sampling the SOF + from hardware asynchronously. + CONFIG_LPC17_USBDEV_EPFAST_INTERRUPT + Enable high priority interrupts. I have no idea why you might want to + do that + CONFIG_LPC17_USBDEV_NDMADESCRIPTORS + Number of DMA descriptors to allocate in SRAM. + CONFIG_LPC17_USBDEV_DMA + Enable lpc17xx-specific DMA support CONFIG_LPC17_USBDEV_NOVBUS Define if the hardware implementation does not support the VBUS signal CONFIG_LPC17_USBDEV_NOLED @@ -472,10 +522,10 @@ Configurations Each Nucleus 2G configuration is maintained in a sudirectory and can be selected as follow: - cd tools - ./configure.sh nucleus2g/ - cd - - . ./setenv.sh + cd tools + ./configure.sh nucleus2g/ + cd - + . ./setenv.sh Where is one of the following: diff --git a/nuttx/configs/olimex-lpc1766stk/README.txt b/nuttx/configs/olimex-lpc1766stk/README.txt index a8bea4d0e..96692688c 100644 --- a/nuttx/configs/olimex-lpc1766stk/README.txt +++ b/nuttx/configs/olimex-lpc1766stk/README.txt @@ -10,7 +10,9 @@ Contents Development Environment GNU Toolchain Options IDEs - NuttX buildroot Toolchain + NuttX EABI "buildroot" Toolchain + NuttX OABI "buildroot" Toolchain + NXFLAT Toolchain LEDs Using OpenOCD and GDB with an FT2232 JTAG emulator Olimex LPC1766-STK Configuration Options @@ -268,8 +270,8 @@ IDEs Startup files will probably cause you some headaches. The NuttX startup file is arch/arm/src/lpc17x/lpc17_vectors.S. -NuttX buildroot Toolchain -^^^^^^^^^^^^^^^^^^^^^^^^^ +NuttX EABI "buildroot" Toolchain +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ A GNU GCC-based toolchain is assumed. The files */setenv.sh should be modified to point to the correct path to the Cortex-M3 GCC toolchain (if @@ -292,7 +294,7 @@ NuttX buildroot Toolchain 4. cd /buildroot - 5. cp configs/cortexm3-defconfig-4.3.3 .config + 5. cp configs/cortexm3-eabi-defconfig-4.6.3 .config 6. make oldconfig @@ -302,10 +304,58 @@ NuttX buildroot Toolchain the path to the newly built binaries. See the file configs/README.txt in the buildroot source tree. That has more - detailed PLUS some special instructions that you will need to follow if you + details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. - NOTE: This is an OABI toolchain. +NuttX OABI "buildroot" Toolchain +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + + The older, OABI buildroot toolchain is also available. To use the OABI + toolchain: + + 1. When building the buildroot toolchain, either (1) modify the cortexm3-eabi-defconfig-4.6.3 + configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI + configuration such as cortexm3-defconfig-4.3.3 + + 2. Modify the Make.defs file to use the OABI converntions: + + +CROSSDEV = arm-nuttx-elf- + +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + -CROSSDEV = arm-nuttx-eabi- + -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + +NXFLAT Toolchain +^^^^^^^^^^^^^^^^ + + If you are *not* using the NuttX buildroot toolchain and you want to use + the NXFLAT tools, then you will still have to build a portion of the buildroot + tools -- just the NXFLAT tools. The buildroot with the NXFLAT tools can + be downloaded from the NuttX SourceForge download site + (https://sourceforge.net/projects/nuttx/files/). + + This GNU toolchain builds and executes in the Linux or Cygwin environment. + + 1. You must have already configured Nuttx in /nuttx. + + cd tools + ./configure.sh lpcxpresso-lpc1768/ + + 2. Download the latest buildroot package into + + 3. unpack the buildroot tarball. The resulting directory may + have versioning information on it like buildroot-x.y.z. If so, + rename /buildroot-x.y.z to /buildroot. + + 4. cd /buildroot + + 5. cp configs/cortexm3-defconfig-nxflat .config + + 6. make oldconfig + + 7. make + + 8. Edit setenv.h, if necessary, so that the PATH variable includes + the path to the newly builtNXFLAT binaries. LEDs ^^^^ @@ -570,177 +620,177 @@ Using OpenOCD and GDB with an FT2232 JTAG emulator Olimex LPC1766-STK Configuration Options ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - CONFIG_ARCH - Identifies the arch/ subdirectory. This should - be set to: + CONFIG_ARCH - Identifies the arch/ subdirectory. This should + be set to: - CONFIG_ARCH=arm + CONFIG_ARCH=arm - CONFIG_ARCH_family - For use in C code: + CONFIG_ARCH_family - For use in C code: - CONFIG_ARCH_ARM=y + CONFIG_ARCH_ARM=y - CONFIG_ARCH_architecture - For use in C code: + CONFIG_ARCH_architecture - For use in C code: - CONFIG_ARCH_CORTEXM3=y + CONFIG_ARCH_CORTEXM3=y - CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory + CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory - CONFIG_ARCH_CHIP=lpc17xx + CONFIG_ARCH_CHIP=lpc17xx - CONFIG_ARCH_CHIP_name - For use in C code to identify the exact - chip: + CONFIG_ARCH_CHIP_name - For use in C code to identify the exact + chip: - CONFIG_ARCH_CHIP_LPC1766=y + CONFIG_ARCH_CHIP_LPC1766=y - CONFIG_ARCH_BOARD - Identifies the configs subdirectory and - hence, the board that supports the particular chip or SoC. + CONFIG_ARCH_BOARD - Identifies the configs subdirectory and + hence, the board that supports the particular chip or SoC. - CONFIG_ARCH_BOARD=olimex-lpc1766stk (for the Olimex LPC1766-STK) + CONFIG_ARCH_BOARD=olimex-lpc1766stk (for the Olimex LPC1766-STK) - CONFIG_ARCH_BOARD_name - For use in C code + CONFIG_ARCH_BOARD_name - For use in C code - CONFIG_ARCH_BOARD_LPC1766STK=y + CONFIG_ARCH_BOARD_LPC1766STK=y - CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation - of delay loops + CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation + of delay loops - CONFIG_ENDIAN_BIG - define if big endian (default is little - endian) + CONFIG_ENDIAN_BIG - define if big endian (default is little + endian) - CONFIG_DRAM_SIZE - Describes the installed DRAM (CPU SRAM in this case): + CONFIG_DRAM_SIZE - Describes the installed DRAM (CPU SRAM in this case): - CONFIG_DRAM_SIZE=(32*1024) (32Kb) + CONFIG_DRAM_SIZE=(32*1024) (32Kb) - There is an additional 32Kb of SRAM in AHB SRAM banks 0 and 1. + There is an additional 32Kb of SRAM in AHB SRAM banks 0 and 1. - CONFIG_DRAM_START - The start address of installed DRAM + CONFIG_DRAM_START - The start address of installed DRAM - CONFIG_DRAM_START=0x10000000 + CONFIG_DRAM_START=0x10000000 - CONFIG_ARCH_IRQPRIO - The LPC17xx supports interrupt prioritization + CONFIG_ARCH_IRQPRIO - The LPC17xx supports interrupt prioritization - CONFIG_ARCH_IRQPRIO=y + CONFIG_ARCH_IRQPRIO=y - CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that - have LEDs + CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that + have LEDs - CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt - stack. If defined, this symbol is the size of the interrupt - stack in bytes. If not defined, the user task stacks will be - used during interrupt handling. + CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt + stack. If defined, this symbol is the size of the interrupt + stack in bytes. If not defined, the user task stacks will be + used during interrupt handling. - CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions + CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions - CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. + CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. - CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that - cause a 100 second delay during boot-up. This 100 second delay - serves no purpose other than it allows you to calibratre - CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure - the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until - the delay actually is 100 seconds. + CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that + cause a 100 second delay during boot-up. This 100 second delay + serves no purpose other than it allows you to calibratre + CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure + the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until + the delay actually is 100 seconds. - Individual subsystems can be enabled: - - CONFIG_LPC17_MAINOSC=y - CONFIG_LPC17_PLL0=y - CONFIG_LPC17_PLL1=n - CONFIG_LPC17_ETHERNET=n - CONFIG_LPC17_USBHOST=n - CONFIG_LPC17_USBOTG=n - CONFIG_LPC17_USBDEV=n - CONFIG_LPC17_UART0=y - CONFIG_LPC17_UART1=n - CONFIG_LPC17_UART2=n - CONFIG_LPC17_UART3=n - CONFIG_LPC17_CAN1=n - CONFIG_LPC17_CAN2=n - CONFIG_LPC17_SPI=n - CONFIG_LPC17_SSP0=n - CONFIG_LPC17_SSP1=n - CONFIG_LPC17_I2C0=n - CONFIG_LPC17_I2C1=n - CONFIG_LPC17_I2S=n - CONFIG_LPC17_TMR0=n - CONFIG_LPC17_TMR1=n - CONFIG_LPC17_TMR2=n - CONFIG_LPC17_TMR3=n - CONFIG_LPC17_RIT=n - CONFIG_LPC17_PWM=n - CONFIG_LPC17_MCPWM=n - CONFIG_LPC17_QEI=n - CONFIG_LPC17_RTC=n - CONFIG_LPC17_WDT=n - CONFIG_LPC17_ADC=n - CONFIG_LPC17_DAC=n - CONFIG_LPC17_GPDMA=n - CONFIG_LPC17_FLASH=n + Individual subsystems can be enabled: + + CONFIG_LPC17_MAINOSC=y + CONFIG_LPC17_PLL0=y + CONFIG_LPC17_PLL1=n + CONFIG_LPC17_ETHERNET=n + CONFIG_LPC17_USBHOST=n + CONFIG_LPC17_USBOTG=n + CONFIG_LPC17_USBDEV=n + CONFIG_LPC17_UART0=y + CONFIG_LPC17_UART1=n + CONFIG_LPC17_UART2=n + CONFIG_LPC17_UART3=n + CONFIG_LPC17_CAN1=n + CONFIG_LPC17_CAN2=n + CONFIG_LPC17_SPI=n + CONFIG_LPC17_SSP0=n + CONFIG_LPC17_SSP1=n + CONFIG_LPC17_I2C0=n + CONFIG_LPC17_I2C1=n + CONFIG_LPC17_I2S=n + CONFIG_LPC17_TMR0=n + CONFIG_LPC17_TMR1=n + CONFIG_LPC17_TMR2=n + CONFIG_LPC17_TMR3=n + CONFIG_LPC17_RIT=n + CONFIG_LPC17_PWM=n + CONFIG_LPC17_MCPWM=n + CONFIG_LPC17_QEI=n + CONFIG_LPC17_RTC=n + CONFIG_LPC17_WDT=n + CONFIG_LPC17_ADC=n + CONFIG_LPC17_DAC=n + CONFIG_LPC17_GPDMA=n + CONFIG_LPC17_FLASH=n LPC17xx specific device driver settings - CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn for the - console and ttys0 (default is the UART0). - CONFIG_UARTn_RXBUFSIZE - Characters are buffered as received. - This specific the size of the receive buffer - CONFIG_UARTn_TXBUFSIZE - Characters are buffered before - being sent. This specific the size of the transmit buffer - CONFIG_UARTn_BAUD - The configure BAUD of the UART. Must be - CONFIG_UARTn_BITS - The number of bits. Must be either 7 or 8. - CONFIG_UARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity - CONFIG_UARTn_2STOP - Two stop bits + CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn for the + console and ttys0 (default is the UART0). + CONFIG_UARTn_RXBUFSIZE - Characters are buffered as received. + This specific the size of the receive buffer + CONFIG_UARTn_TXBUFSIZE - Characters are buffered before + being sent. This specific the size of the transmit buffer + CONFIG_UARTn_BAUD - The configure BAUD of the UART. Must be + CONFIG_UARTn_BITS - The number of bits. Must be either 7 or 8. + CONFIG_UARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity + CONFIG_UARTn_2STOP - Two stop bits LPC17xx specific CAN device driver settings. These settings all require CONFIG_CAN: - CONFIG_CAN_EXTID - Enables support for the 29-bit extended ID. Default - Standard 11-bit IDs. - CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN1 is defined. - CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN2 is defined. - CONFIG_CAN1_DIVISOR - CAN1 is clocked at CCLK divided by this number. - (the CCLK frequency is divided by this number to get the CAN clock). - Options = {1,2,4,6}. Default: 4. - CONFIG_CAN2_DIVISOR - CAN2 is clocked at CCLK divided by this number. - (the CCLK frequency is divided by this number to get the CAN clock). - Options = {1,2,4,6}. Default: 4. - CONFIG_CAN_TSEG1 - The number of CAN time quanta in segment 1. Default: 6 - CONFIG_CAN_TSEG2 - the number of CAN time quanta in segment 2. Default: 7 + CONFIG_CAN_EXTID - Enables support for the 29-bit extended ID. Default + Standard 11-bit IDs. + CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN1 is defined. + CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN2 is defined. + CONFIG_CAN1_DIVISOR - CAN1 is clocked at CCLK divided by this number. + (the CCLK frequency is divided by this number to get the CAN clock). + Options = {1,2,4,6}. Default: 4. + CONFIG_CAN2_DIVISOR - CAN2 is clocked at CCLK divided by this number. + (the CCLK frequency is divided by this number to get the CAN clock). + Options = {1,2,4,6}. Default: 4. + CONFIG_CAN_TSEG1 - The number of CAN time quanta in segment 1. Default: 6 + CONFIG_CAN_TSEG2 - the number of CAN time quanta in segment 2. Default: 7 LPC17xx specific PHY/Ethernet device driver settings. These setting also require CONFIG_NET and CONFIG_LPC17_ETHERNET. - CONFIG_PHY_KS8721 - Selects Micrel KS8721 PHY - CONFIG_PHY_AUTONEG - Enable auto-negotion - CONFIG_PHY_SPEED100 - Select 100Mbit vs. 10Mbit speed. - CONFIG_PHY_FDUPLEX - Select full (vs. half) duplex + CONFIG_PHY_KS8721 - Selects Micrel KS8721 PHY + CONFIG_PHY_AUTONEG - Enable auto-negotion + CONFIG_PHY_SPEED100 - Select 100Mbit vs. 10Mbit speed. + CONFIG_PHY_FDUPLEX - Select full (vs. half) duplex CONFIG_NET_EMACRAM_SIZE - Size of EMAC RAM. Default: 16Kb - CONFIG_NET_NTXDESC - Configured number of Tx descriptors. Default: 18 - CONFIG_NET_NRXDESC - Configured number of Rx descriptors. Default: 18 - CONFIG_NET_PRIORITY - Ethernet interrupt priority. The is default is - the higest priority. - CONFIG_NET_WOL - Enable Wake-up on Lan (not fully implemented). - CONFIG_NET_REGDEBUG - Enabled low level register debug. Also needs - CONFIG_DEBUG. - CONFIG_NET_DUMPPACKET - Dump all received and transmitted packets. - Also needs CONFIG_DEBUG. - CONFIG_NET_HASH - Enable receipt of near-perfect match frames. - CONFIG_NET_MULTICAST - Enable receipt of multicast (and unicast) frames. - Automatically set if CONFIG_NET_IGMP is selected. + CONFIG_NET_NTXDESC - Configured number of Tx descriptors. Default: 18 + CONFIG_NET_NRXDESC - Configured number of Rx descriptors. Default: 18 + CONFIG_NET_PRIORITY - Ethernet interrupt priority. The is default is + the higest priority. + CONFIG_NET_WOL - Enable Wake-up on Lan (not fully implemented). + CONFIG_NET_REGDEBUG - Enabled low level register debug. Also needs + CONFIG_DEBUG. + CONFIG_NET_DUMPPACKET - Dump all received and transmitted packets. + Also needs CONFIG_DEBUG. + CONFIG_NET_HASH - Enable receipt of near-perfect match frames. + CONFIG_NET_MULTICAST - Enable receipt of multicast (and unicast) frames. + Automatically set if CONFIG_NET_IGMP is selected. LPC17xx USB Device Configuration - CONFIG_LPC17_USBDEV_FRAME_INTERRUPT - Handle USB Start-Of-Frame events. - Enable reading SOF from interrupt handler vs. simply reading on demand. - Probably a bad idea... Unless there is some issue with sampling the SOF - from hardware asynchronously. - CONFIG_LPC17_USBDEV_EPFAST_INTERRUPT - Enable high priority interrupts. I have no idea why you might want to - do that - CONFIG_LPC17_USBDEV_NDMADESCRIPTORS - Number of DMA descriptors to allocate in SRAM. - CONFIG_LPC17_USBDEV_DMA - Enable lpc17xx-specific DMA support + CONFIG_LPC17_USBDEV_FRAME_INTERRUPT + Handle USB Start-Of-Frame events. + Enable reading SOF from interrupt handler vs. simply reading on demand. + Probably a bad idea... Unless there is some issue with sampling the SOF + from hardware asynchronously. + CONFIG_LPC17_USBDEV_EPFAST_INTERRUPT + Enable high priority interrupts. I have no idea why you might want to + do that + CONFIG_LPC17_USBDEV_NDMADESCRIPTORS + Number of DMA descriptors to allocate in SRAM. + CONFIG_LPC17_USBDEV_DMA + Enable lpc17xx-specific DMA support CONFIG_LPC17_USBDEV_NOVBUS Define if the hardware implementation does not support the VBUS signal CONFIG_LPC17_USBDEV_NOLED @@ -800,10 +850,10 @@ Configurations Each Olimex LPC1766-STK configuration is maintained in a sudirectory and can be selected as follow: - cd tools - ./configure.sh olimex-lpc1766stk/ - cd - - . ./setenv.sh + cd tools + ./configure.sh olimex-lpc1766stk/ + cd - + . ./setenv.sh Where is one of the following: diff --git a/nuttx/configs/sam3u-ek/README.txt b/nuttx/configs/sam3u-ek/README.txt index 435e30a49..b13c68945 100644 --- a/nuttx/configs/sam3u-ek/README.txt +++ b/nuttx/configs/sam3u-ek/README.txt @@ -10,7 +10,9 @@ Contents - Development Environment - GNU Toolchain Options - IDEs - - NuttX buildroot Toolchain + - NuttX EABI "buildroot" Toolchain + - NuttX OABI "buildroot" Toolchain + - NXFLAT Toolchain - LEDs - SAM3U-EK-specific Configuration Options - Configurations @@ -42,7 +44,7 @@ GNU Toolchain Options CONFIG_SAM3U_CODESOURCERYW=y : CodeSourcery under Windows CONFIG_SAM3U_CODESOURCERYL=y : CodeSourcery under Linux CONFIG_SAM3U_DEVKITARM=y : devkitARM under Windows - CONFIG_SAM3U_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default) + CONFIG_SAM3U_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default) If you are not using CONFIG_SAM3U_BUILDROOT, then you may also have to modify the PATH in the setenv.h file if your make cannot find the tools. @@ -123,8 +125,8 @@ IDEs one time from the Cygwin command line in order to obtain the pre-built startup object needed by RIDE. -NuttX buildroot Toolchain -^^^^^^^^^^^^^^^^^^^^^^^^^ +NuttX EABI "buildroot" Toolchain +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ A GNU GCC-based toolchain is assumed. The files */setenv.sh should be modified to point to the correct path to the Cortex-M3 GCC toolchain (if @@ -147,7 +149,7 @@ NuttX buildroot Toolchain 4. cd /buildroot - 5. cp configs/cortexm3-defconfig-4.3.3 .config + 5. cp configs/cortexm3-eabi-defconfig-4.6.3 .config 6. make oldconfig @@ -157,9 +159,59 @@ NuttX buildroot Toolchain the path to the newly built binaries. See the file configs/README.txt in the buildroot source tree. That has more - detailed PLUS some special instructions that you will need to follow if you are + details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. +NuttX OABI "buildroot" Toolchain +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + + The older, OABI buildroot toolchain is also available. To use the OABI + toolchain: + + 1. When building the buildroot toolchain, either (1) modify the cortexm3-eabi-defconfig-4.6.3 + configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI + configuration such as cortexm3-defconfig-4.3.3 + + 2. Modify the Make.defs file to use the OABI converntions: + + +CROSSDEV = arm-nuttx-elf- + +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + -CROSSDEV = arm-nuttx-eabi- + -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + +NXFLAT Toolchain +^^^^^^^^^^^^^^^^ + + If you are *not* using the NuttX buildroot toolchain and you want to use + the NXFLAT tools, then you will still have to build a portion of the buildroot + tools -- just the NXFLAT tools. The buildroot with the NXFLAT tools can + be downloaded from the NuttX SourceForge download site + (https://sourceforge.net/projects/nuttx/files/). + + This GNU toolchain builds and executes in the Linux or Cygwin environment. + + 1. You must have already configured Nuttx in /nuttx. + + cd tools + ./configure.sh lpcxpresso-lpc1768/ + + 2. Download the latest buildroot package into + + 3. unpack the buildroot tarball. The resulting directory may + have versioning information on it like buildroot-x.y.z. If so, + rename /buildroot-x.y.z to /buildroot. + + 4. cd /buildroot + + 5. cp configs/cortexm3-defconfig-nxflat .config + + 6. make oldconfig + + 7. make + + 8. Edit setenv.h, if necessary, so that the PATH variable includes + the path to the newly builtNXFLAT binaries. + LEDs ^^^^ @@ -167,16 +219,16 @@ The SAM3U-EK board has four LEDs labeled LD1, LD2, LD3 and LD4 on the the board. Usage of these LEDs is defined in include/board.h and src/up_leds.c. They are encoded as follows: - SYMBOL Meaning LED0* LED1 LED2 - ------------------- ----------------------- ------- ------- ------- - LED_STARTED NuttX has been started OFF OFF OFF - LED_HEAPALLOCATE Heap has been allocated OFF OFF ON - LED_IRQSENABLED Interrupts enabled OFF ON OFF - LED_STACKCREATED Idle stack created OFF ON ON - LED_INIRQ In an interrupt** N/C FLASH N/C - LED_SIGNAL In a signal handler*** N/C N/C FLASH - LED_ASSERTION An assertion failed FLASH N/C N/C - LED_PANIC The system has crashed FLASH N/C N/C + SYMBOL Meaning LED0* LED1 LED2 + ------------------- ----------------------- ------- ------- ------- + LED_STARTED NuttX has been started OFF OFF OFF + LED_HEAPALLOCATE Heap has been allocated OFF OFF ON + LED_IRQSENABLED Interrupts enabled OFF ON OFF + LED_STACKCREATED Idle stack created OFF ON ON + LED_INIRQ In an interrupt** N/C FLASH N/C + LED_SIGNAL In a signal handler*** N/C N/C FLASH + LED_ASSERTION An assertion failed FLASH N/C N/C + LED_PANIC The system has crashed FLASH N/C N/C * If LED1 and LED2 are statically on, then NuttX probably failed to boot and these LEDs will give you some indication of where the failure was @@ -188,116 +240,116 @@ They are encoded as follows: SAM3U-EK-specific Configuration Options ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - CONFIG_ARCH - Identifies the arch/ subdirectory. This should - be set to: + CONFIG_ARCH - Identifies the arch/ subdirectory. This should + be set to: - CONFIG_ARCH=arm + CONFIG_ARCH=arm - CONFIG_ARCH_family - For use in C code: + CONFIG_ARCH_family - For use in C code: - CONFIG_ARCH_ARM=y + CONFIG_ARCH_ARM=y - CONFIG_ARCH_architecture - For use in C code: + CONFIG_ARCH_architecture - For use in C code: - CONFIG_ARCH_CORTEXM3=y + CONFIG_ARCH_CORTEXM3=y - CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory + CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory - CONFIG_ARCH_CHIP=sam3u + CONFIG_ARCH_CHIP=sam3u - CONFIG_ARCH_CHIP_name - For use in C code to identify the exact - chip: + CONFIG_ARCH_CHIP_name - For use in C code to identify the exact + chip: - CONFIG_ARCH_CHIP_AT91SAM3U4 + CONFIG_ARCH_CHIP_AT91SAM3U4 - CONFIG_ARCH_BOARD - Identifies the configs subdirectory and - hence, the board that supports the particular chip or SoC. + CONFIG_ARCH_BOARD - Identifies the configs subdirectory and + hence, the board that supports the particular chip or SoC. - CONFIG_ARCH_BOARD=sam3u_ek (for the SAM3U-EK development board) + CONFIG_ARCH_BOARD=sam3u_ek (for the SAM3U-EK development board) - CONFIG_ARCH_BOARD_name - For use in C code + CONFIG_ARCH_BOARD_name - For use in C code - CONFIG_ARCH_BOARD_SAM3UEK=y + CONFIG_ARCH_BOARD_SAM3UEK=y - CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation - of delay loops + CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation + of delay loops - CONFIG_ENDIAN_BIG - define if big endian (default is little - endian) + CONFIG_ENDIAN_BIG - define if big endian (default is little + endian) - CONFIG_DRAM_SIZE - Describes the installed DRAM (SRAM in this case): + CONFIG_DRAM_SIZE - Describes the installed DRAM (SRAM in this case): - CONFIG_DRAM_SIZE=0x0000c000 (48Kb) + CONFIG_DRAM_SIZE=0x0000c000 (48Kb) - CONFIG_DRAM_START - The start address of installed DRAM + CONFIG_DRAM_START - The start address of installed DRAM - CONFIG_DRAM_START=0x20000000 + CONFIG_DRAM_START=0x20000000 - CONFIG_ARCH_IRQPRIO - The SAM3UF103Z supports interrupt prioritization + CONFIG_ARCH_IRQPRIO - The SAM3UF103Z supports interrupt prioritization - CONFIG_ARCH_IRQPRIO=y + CONFIG_ARCH_IRQPRIO=y - CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that - have LEDs + CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that + have LEDs - CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt - stack. If defined, this symbol is the size of the interrupt - stack in bytes. If not defined, the user task stacks will be - used during interrupt handling. + CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt + stack. If defined, this symbol is the size of the interrupt + stack in bytes. If not defined, the user task stacks will be + used during interrupt handling. - CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions + CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions - CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. + CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. - CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that - cause a 100 second delay during boot-up. This 100 second delay - serves no purpose other than it allows you to calibratre - CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure - the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until - the delay actually is 100 seconds. + CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that + cause a 100 second delay during boot-up. This 100 second delay + serves no purpose other than it allows you to calibratre + CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure + the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until + the delay actually is 100 seconds. Individual subsystems can be enabled: - CONFIG_SAM3U_DMA - CONFIG_SAM3U_HSMCI - CONFIG_SAM3U_NAND - CONFIG_SAM3U_SPI - CONFIG_SAM3U_UART - CONFIG_SAM3U_USART0 - CONFIG_SAM3U_USART1 - CONFIG_SAM3U_USART2 - CONFIG_SAM3U_USART3 + CONFIG_SAM3U_DMA + CONFIG_SAM3U_HSMCI + CONFIG_SAM3U_NAND + CONFIG_SAM3U_SPI + CONFIG_SAM3U_UART + CONFIG_SAM3U_USART0 + CONFIG_SAM3U_USART1 + CONFIG_SAM3U_USART2 + CONFIG_SAM3U_USART3 Some subsystems can be configured to operate in different ways. The drivers need to know how to configure the subsystem. - CONFIG_GPIOA_IRQ - CONFIG_GPIOB_IRQ - CONFIG_GPIOC_IRQ - CONFIG_USART0_ISUART - CONFIG_USART1_ISUART - CONFIG_USART2_ISUART - CONFIG_USART3_ISUART + CONFIG_GPIOA_IRQ + CONFIG_GPIOB_IRQ + CONFIG_GPIOC_IRQ + CONFIG_USART0_ISUART + CONFIG_USART1_ISUART + CONFIG_USART2_ISUART + CONFIG_USART3_ISUART AT91SAM3U specific device driver settings - CONFIG_U[S]ARTn_SERIAL_CONSOLE - selects the USARTn (n=0,1,2,3) or UART + CONFIG_U[S]ARTn_SERIAL_CONSOLE - selects the USARTn (n=0,1,2,3) or UART m (m=4,5) for the console and ttys0 (default is the USART1). - CONFIG_U[S]ARTn_RXBUFSIZE - Characters are buffered as received. - This specific the size of the receive buffer - CONFIG_U[S]ARTn_TXBUFSIZE - Characters are buffered before - being sent. This specific the size of the transmit buffer - CONFIG_U[S]ARTn_BAUD - The configure BAUD of the UART. Must be - CONFIG_U[S]ARTn_BITS - The number of bits. Must be either 7 or 8. - CONFIG_U[S]ARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity - CONFIG_U[S]ARTn_2STOP - Two stop bits + CONFIG_U[S]ARTn_RXBUFSIZE - Characters are buffered as received. + This specific the size of the receive buffer + CONFIG_U[S]ARTn_TXBUFSIZE - Characters are buffered before + being sent. This specific the size of the transmit buffer + CONFIG_U[S]ARTn_BAUD - The configure BAUD of the UART. Must be + CONFIG_U[S]ARTn_BITS - The number of bits. Must be either 7 or 8. + CONFIG_U[S]ARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity + CONFIG_U[S]ARTn_2STOP - Two stop bits LCD Options. Other than the standard LCD configuration options (see configs/README.txt), the SAM3U-EK driver also supports: - CONFIG_LCD_PORTRAIT - Present the display in the standard 240x320 - "Portrait" orientation. Default: The display is rotated to - support a 320x240 "Landscape" orientation. + CONFIG_LCD_PORTRAIT - Present the display in the standard 240x320 + "Portrait" orientation. Default: The display is rotated to + support a 320x240 "Landscape" orientation. Configurations ^^^^^^^^^^^^^^ @@ -305,10 +357,10 @@ Configurations Each SAM3U-EK configuration is maintained in a sudirectory and can be selected as follow: - cd tools - ./configure.sh sam3u-ek/ - cd - - . ./setenv.sh + cd tools + ./configure.sh sam3u-ek/ + cd - + . ./setenv.sh Before sourcing the setenv.sh file above, you should examine it and perform edits as necessary so that BUILDROOT_BIN is the correct path to the directory @@ -317,7 +369,7 @@ than holds your toolchain binaries. And then build NuttX by simply typing the following. At the conclusion of the make, the nuttx binary will reside in an ELF file called, simply, nuttx. - make + make The that is provided above as an argument to the tools/configure.sh must be is one of the following: @@ -328,7 +380,7 @@ must be is one of the following: are built separately. This build requires a special make command; not just 'make' but make with the following two arguments: - make pass1 pass2 + make pass1 pass2 This is required because in the normal case (just 'make'), make will create all dependencies then execute the pass1 and pass2 targets. But @@ -336,16 +388,16 @@ must be is one of the following: This specall make command ('make pass1 pass2') will make the dependencies separately for each pass. - At there end of the build, there four files will top-level build - directory: + At there end of the build, there four files will top-level build + directory: - nuttx_user.elf - The pass1 ELF file - nuttx - The pass2 ELF file - nuttx_user.hex - The pass1 Intel HEX format file - nuttx.hex - The pass2 Intel HEX file + nuttx_user.elf - The pass1 ELF file + nuttx - The pass2 ELF file + nuttx_user.hex - The pass1 Intel HEX format file + nuttx.hex - The pass2 Intel HEX file - The J-Link program will except files in .hex, .mot, .srec, and .bin - formats. + The J-Link program will except files in .hex, .mot, .srec, and .bin + formats. nsh: Configures the NuttShell (nsh) located at examples/nsh. The diff --git a/nuttx/configs/stm3210e-eval/README.txt b/nuttx/configs/stm3210e-eval/README.txt index f68ce26de..704fadb62 100644 --- a/nuttx/configs/stm3210e-eval/README.txt +++ b/nuttx/configs/stm3210e-eval/README.txt @@ -10,7 +10,9 @@ Contents - Development Environment - GNU Toolchain Options - IDEs - - NuttX buildroot Toolchain + - NuttX EABI "buildroot" Toolchain + - NuttX OABI "buildroot" Toolchain + - NXFLAT Toolchain - DFU and JTAG - OpenOCD - LEDs @@ -131,8 +133,8 @@ IDEs one time from the Cygwin command line in order to obtain the pre-built startup object needed by RIDE. -NuttX buildroot Toolchain -========================= +NuttX EABI "buildroot" Toolchain +================================ A GNU GCC-based toolchain is assumed. The files */setenv.sh should be modified to point to the correct path to the Cortex-M3 GCC toolchain (if @@ -155,7 +157,7 @@ NuttX buildroot Toolchain 4. cd /buildroot - 5. cp configs/cortexm3-defconfig-4.3.3 .config + 5. cp configs/cortexm3-eabi-defconfig-4.6.3 .config 6. make oldconfig @@ -165,9 +167,59 @@ NuttX buildroot Toolchain the path to the newly built binaries. See the file configs/README.txt in the buildroot source tree. That has more - detailed PLUS some special instructions that you will need to follow if you are + details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. +NuttX OABI "buildroot" Toolchain +================================ + + The older, OABI buildroot toolchain is also available. To use the OABI + toolchain: + + 1. When building the buildroot toolchain, either (1) modify the cortexm3-eabi-defconfig-4.6.3 + configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI + configuration such as cortexm3-defconfig-4.3.3 + + 2. Modify the Make.defs file to use the OABI converntions: + + +CROSSDEV = arm-nuttx-elf- + +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + -CROSSDEV = arm-nuttx-eabi- + -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + +NXFLAT Toolchain +================ + + If you are *not* using the NuttX buildroot toolchain and you want to use + the NXFLAT tools, then you will still have to build a portion of the buildroot + tools -- just the NXFLAT tools. The buildroot with the NXFLAT tools can + be downloaded from the NuttX SourceForge download site + (https://sourceforge.net/projects/nuttx/files/). + + This GNU toolchain builds and executes in the Linux or Cygwin environment. + + 1. You must have already configured Nuttx in /nuttx. + + cd tools + ./configure.sh lpcxpresso-lpc1768/ + + 2. Download the latest buildroot package into + + 3. unpack the buildroot tarball. The resulting directory may + have versioning information on it like buildroot-x.y.z. If so, + rename /buildroot-x.y.z to /buildroot. + + 4. cd /buildroot + + 5. cp configs/cortexm3-defconfig-nxflat .config + + 6. make oldconfig + + 7. make + + 8. Edit setenv.h, if necessary, so that the PATH variable includes + the path to the newly builtNXFLAT binaries. + DFU and JTAG ============ diff --git a/nuttx/configs/stm3220g-eval/README.txt b/nuttx/configs/stm3220g-eval/README.txt index 22038893e..79311150d 100644 --- a/nuttx/configs/stm3220g-eval/README.txt +++ b/nuttx/configs/stm3220g-eval/README.txt @@ -10,7 +10,9 @@ Contents - Development Environment - GNU Toolchain Options - IDEs - - NuttX buildroot Toolchain + - NuttX EABI "buildroot" Toolchain + - NuttX OABI "buildroot" Toolchain + - NXFLAT Toolchain - STM3220G-EVAL-specific Configuration Options - LEDs - Ethernet @@ -170,8 +172,8 @@ IDEs one time from the Cygwin command line in order to obtain the pre-built startup object needed by RIDE. -NuttX buildroot Toolchain -========================= +NuttX EABI "buildroot" Toolchain +================================ A GNU GCC-based toolchain is assumed. The files */setenv.sh should be modified to point to the correct path to the Cortex-M3 GCC toolchain (if @@ -194,7 +196,7 @@ NuttX buildroot Toolchain 4. cd /buildroot - 5. cp configs/cortexm3-defconfig-4.3.3 .config + 5. cp configs/cortexm3-eabi-defconfig-4.6.3 .config 6. make oldconfig @@ -204,9 +206,59 @@ NuttX buildroot Toolchain the path to the newly built binaries. See the file configs/README.txt in the buildroot source tree. That has more - detailed PLUS some special instructions that you will need to follow if you are + details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. +NuttX OABI "buildroot" Toolchain +================================ + + The older, OABI buildroot toolchain is also available. To use the OABI + toolchain: + + 1. When building the buildroot toolchain, either (1) modify the cortexm3-eabi-defconfig-4.6.3 + configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI + configuration such as cortexm3-defconfig-4.3.3 + + 2. Modify the Make.defs file to use the OABI converntions: + + +CROSSDEV = arm-nuttx-elf- + +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + -CROSSDEV = arm-nuttx-eabi- + -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + +NXFLAT Toolchain +================ + + If you are *not* using the NuttX buildroot toolchain and you want to use + the NXFLAT tools, then you will still have to build a portion of the buildroot + tools -- just the NXFLAT tools. The buildroot with the NXFLAT tools can + be downloaded from the NuttX SourceForge download site + (https://sourceforge.net/projects/nuttx/files/). + + This GNU toolchain builds and executes in the Linux or Cygwin environment. + + 1. You must have already configured Nuttx in /nuttx. + + cd tools + ./configure.sh lpcxpresso-lpc1768/ + + 2. Download the latest buildroot package into + + 3. unpack the buildroot tarball. The resulting directory may + have versioning information on it like buildroot-x.y.z. If so, + rename /buildroot-x.y.z to /buildroot. + + 4. cd /buildroot + + 5. cp configs/cortexm3-defconfig-nxflat .config + + 6. make oldconfig + + 7. make + + 8. Edit setenv.h, if necessary, so that the PATH variable includes + the path to the newly builtNXFLAT binaries. + Ethernet ======== diff --git a/nuttx/configs/stm3240g-eval/README.txt b/nuttx/configs/stm3240g-eval/README.txt index a1a596bae..d77609e12 100644 --- a/nuttx/configs/stm3240g-eval/README.txt +++ b/nuttx/configs/stm3240g-eval/README.txt @@ -10,7 +10,9 @@ Contents - Development Environment - GNU Toolchain Options - IDEs - - NuttX buildroot Toolchain + - NuttX EABI "buildroot" Toolchain + - NuttX OABI "buildroot" Toolchain + - NXFLAT Toolchain - STM3240G-EVAL-specific Configuration Options - LEDs - Ethernet @@ -177,8 +179,8 @@ IDEs one time from the Cygwin command line in order to obtain the pre-built startup object needed by RIDE. -NuttX buildroot Toolchain -========================= +NuttX EABI "buildroot" Toolchain +================================ A GNU GCC-based toolchain is assumed. The files */setenv.sh should be modified to point to the correct path to the Cortex-M3 GCC toolchain (if @@ -201,7 +203,7 @@ NuttX buildroot Toolchain 4. cd /buildroot - 5. cp configs/cortexm3-defconfig-4.3.3 .config + 5. cp configs/cortexm3-eabi-defconfig-4.6.3 .config 6. make oldconfig @@ -211,9 +213,59 @@ NuttX buildroot Toolchain the path to the newly built binaries. See the file configs/README.txt in the buildroot source tree. That has more - detailed PLUS some special instructions that you will need to follow if you are + details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. +NuttX OABI "buildroot" Toolchain +================================ + + The older, OABI buildroot toolchain is also available. To use the OABI + toolchain: + + 1. When building the buildroot toolchain, either (1) modify the cortexm3-eabi-defconfig-4.6.3 + configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI + configuration such as cortexm3-defconfig-4.3.3 + + 2. Modify the Make.defs file to use the OABI converntions: + + +CROSSDEV = arm-nuttx-elf- + +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + -CROSSDEV = arm-nuttx-eabi- + -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + +NXFLAT Toolchain +================ + + If you are *not* using the NuttX buildroot toolchain and you want to use + the NXFLAT tools, then you will still have to build a portion of the buildroot + tools -- just the NXFLAT tools. The buildroot with the NXFLAT tools can + be downloaded from the NuttX SourceForge download site + (https://sourceforge.net/projects/nuttx/files/). + + This GNU toolchain builds and executes in the Linux or Cygwin environment. + + 1. You must have already configured Nuttx in /nuttx. + + cd tools + ./configure.sh lpcxpresso-lpc1768/ + + 2. Download the latest buildroot package into + + 3. unpack the buildroot tarball. The resulting directory may + have versioning information on it like buildroot-x.y.z. If so, + rename /buildroot-x.y.z to /buildroot. + + 4. cd /buildroot + + 5. cp configs/cortexm3-defconfig-nxflat .config + + 6. make oldconfig + + 7. make + + 8. Edit setenv.h, if necessary, so that the PATH variable includes + the path to the newly builtNXFLAT binaries. + Ethernet ======== diff --git a/nuttx/configs/stm32f4discovery/README.txt b/nuttx/configs/stm32f4discovery/README.txt index baf5184e3..65b4bf752 100644 --- a/nuttx/configs/stm32f4discovery/README.txt +++ b/nuttx/configs/stm32f4discovery/README.txt @@ -10,7 +10,9 @@ Contents - Development Environment - GNU Toolchain Options - IDEs - - NuttX buildroot Toolchain + - NuttX EABI "buildroot" Toolchain + - NuttX OABI "buildroot" Toolchain + - NXFLAT Toolchain - LEDs - PWM - UARTs @@ -174,8 +176,8 @@ IDEs one time from the Cygwin command line in order to obtain the pre-built startup object needed by RIDE. -NuttX buildroot Toolchain -========================= +NuttX EABI "buildroot" Toolchain +================================ A GNU GCC-based toolchain is assumed. The files */setenv.sh should be modified to point to the correct path to the Cortex-M3 GCC toolchain (if @@ -198,7 +200,7 @@ NuttX buildroot Toolchain 4. cd /buildroot - 5. cp configs/cortexm3-defconfig-4.3.3 .config + 5. cp configs/cortexm3-eabi-defconfig-4.6.3 .config 6. make oldconfig @@ -208,9 +210,59 @@ NuttX buildroot Toolchain the path to the newly built binaries. See the file configs/README.txt in the buildroot source tree. That has more - detailed PLUS some special instructions that you will need to follow if you are + details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. +NuttX OABI "buildroot" Toolchain +================================ + + The older, OABI buildroot toolchain is also available. To use the OABI + toolchain: + + 1. When building the buildroot toolchain, either (1) modify the cortexm3-eabi-defconfig-4.6.3 + configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI + configuration such as cortexm3-defconfig-4.3.3 + + 2. Modify the Make.defs file to use the OABI converntions: + + +CROSSDEV = arm-nuttx-elf- + +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + -CROSSDEV = arm-nuttx-eabi- + -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + +NXFLAT Toolchain +================ + + If you are *not* using the NuttX buildroot toolchain and you want to use + the NXFLAT tools, then you will still have to build a portion of the buildroot + tools -- just the NXFLAT tools. The buildroot with the NXFLAT tools can + be downloaded from the NuttX SourceForge download site + (https://sourceforge.net/projects/nuttx/files/). + + This GNU toolchain builds and executes in the Linux or Cygwin environment. + + 1. You must have already configured Nuttx in /nuttx. + + cd tools + ./configure.sh lpcxpresso-lpc1768/ + + 2. Download the latest buildroot package into + + 3. unpack the buildroot tarball. The resulting directory may + have versioning information on it like buildroot-x.y.z. If so, + rename /buildroot-x.y.z to /buildroot. + + 4. cd /buildroot + + 5. cp configs/cortexm3-defconfig-nxflat .config + + 6. make oldconfig + + 7. make + + 8. Edit setenv.h, if necessary, so that the PATH variable includes + the path to the newly builtNXFLAT binaries. + LEDs ==== diff --git a/nuttx/configs/twr-k60n512/README.txt b/nuttx/configs/twr-k60n512/README.txt index ccf81508c..3ac70cf7e 100644 --- a/nuttx/configs/twr-k60n512/README.txt +++ b/nuttx/configs/twr-k60n512/README.txt @@ -23,7 +23,9 @@ Contents o Development Environment o GNU Toolchain Options o IDEs - o NuttX buildroot Toolchain + o NuttX EABI "buildroot" Toolchain + o NuttX OABI "buildroot" Toolchain + o NXFLAT Toolchain Kinetis TWR-K60N512 Features: ============================= @@ -264,17 +266,17 @@ The TWR-K60N100 board has four LEDs labeled D2..D4 on the board. Usage of these LEDs is defined in include/board.h and src/up_leds.c. They are encoded as follows: - SYMBOL Meaning LED1* LED2 LED3 LED4 - ------------------- ----------------------- ------- ------- ------- ------ - LED_STARTED NuttX has been started ON OFF OFF OFF - LED_HEAPALLOCATE Heap has been allocated OFF ON OFF OFF - LED_IRQSENABLED Interrupts enabled ON ON OFF OFF - LED_STACKCREATED Idle stack created OFF OFF ON OFF - LED_INIRQ In an interrupt** ON N/C N/C OFF - LED_SIGNAL In a signal handler*** N/C ON N/C OFF - LED_ASSERTION An assertion failed ON ON N/C OFF - LED_PANIC The system has crashed N/C N/C N/C ON - LED_IDLE STM32 is is sleep mode (Optional, not used) + SYMBOL Meaning LED1* LED2 LED3 LED4 + ------------------- ----------------------- ------- ------- ------- ------ + LED_STARTED NuttX has been started ON OFF OFF OFF + LED_HEAPALLOCATE Heap has been allocated OFF ON OFF OFF + LED_IRQSENABLED Interrupts enabled ON ON OFF OFF + LED_STACKCREATED Idle stack created OFF OFF ON OFF + LED_INIRQ In an interrupt** ON N/C N/C OFF + LED_SIGNAL In a signal handler*** N/C ON N/C OFF + LED_ASSERTION An assertion failed ON ON N/C OFF + LED_PANIC The system has crashed N/C N/C N/C ON + LED_IDLE STM32 is is sleep mode (Optional, not used) * If LED1, LED2, LED3 are statically on, then NuttX probably failed to boot and these LEDs will give you some indication of where the failure was @@ -308,7 +310,7 @@ GNU Toolchain Options CONFIG_KINETIS_CODESOURCERYW=y : CodeSourcery under Windows CONFIG_KINETIS_CODESOURCERYL=y : CodeSourcery under Linux CONFIG_KINETIS_DEVKITARM=y : devkitARM under Windows - CONFIG_KINETIS_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default) + CONFIG_KINETIS_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default) If you are not using CONFIG_KINETIS_BUILDROOT, then you may also have to modify the PATH in the setenv.h file if your make cannot find the tools. @@ -386,8 +388,8 @@ IDEs Startup files will probably cause you some headaches. The NuttX startup file is arch/arm/src/kinetis/k40_vectors.S. -NuttX buildroot Toolchain -========================= +NuttX EABI "buildroot" Toolchain +================================ A GNU GCC-based toolchain is assumed. The files */setenv.sh should be modified to point to the correct path to the Cortex-M4 GCC toolchain (if @@ -397,8 +399,7 @@ NuttX buildroot Toolchain SourceForge download site (https://sourceforge.net/projects/nuttx/files/buildroot/). This GNU toolchain builds and executes in the Linux or Cygwin environment. - NOTE: The NuttX toolchain is an OABI toolchain (vs. the more common EABI) - and does not include optimizations for Cortex-M4 (ARMv7E-M). + NOTE: The NuttX toolchain may not include optimizations for Cortex-M4 (ARMv7E-M). 1. You must have already configured Nuttx in /nuttx. @@ -413,7 +414,7 @@ NuttX buildroot Toolchain 4. cd /buildroot - 5. cp configs/cortexm3-defconfig-4.3.3 .config + 5. cp configs/cortexm3-eabi-defconfig-4.6.3 .config 6. make oldconfig @@ -423,92 +424,142 @@ NuttX buildroot Toolchain the path to the newly built binaries. See the file configs/README.txt in the buildroot source tree. That has more - detailed PLUS some special instructions that you will need to follow if you are + details PLUS some special instructions that you will need to follow if you are building a Cortex-M4 toolchain for Cygwin under Windows. +NuttX OABI "buildroot" Toolchain +================================ + + The older, OABI buildroot toolchain is also available. To use the OABI + toolchain: + + 1. When building the buildroot toolchain, either (1) modify the cortexm3-eabi-defconfig-4.6.3 + configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI + configuration such as cortexm3-defconfig-4.3.3 + + 2. Modify the Make.defs file to use the OABI converntions: + + +CROSSDEV = arm-nuttx-elf- + +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + -CROSSDEV = arm-nuttx-eabi- + -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + +NXFLAT Toolchain +================ + + If you are *not* using the NuttX buildroot toolchain and you want to use + the NXFLAT tools, then you will still have to build a portion of the buildroot + tools -- just the NXFLAT tools. The buildroot with the NXFLAT tools can + be downloaded from the NuttX SourceForge download site + (https://sourceforge.net/projects/nuttx/files/). + + This GNU toolchain builds and executes in the Linux or Cygwin environment. + + 1. You must have already configured Nuttx in /nuttx. + + cd tools + ./configure.sh lpcxpresso-lpc1768/ + + 2. Download the latest buildroot package into + + 3. unpack the buildroot tarball. The resulting directory may + have versioning information on it like buildroot-x.y.z. If so, + rename /buildroot-x.y.z to /buildroot. + + 4. cd /buildroot + + 5. cp configs/cortexm3-defconfig-nxflat .config + + 6. make oldconfig + + 7. make + + 8. Edit setenv.h, if necessary, so that the PATH variable includes + the path to the newly builtNXFLAT binaries. + TWR-K60N512-specific Configuration Options ========================================== - CONFIG_ARCH - Identifies the arch/ subdirectory. This sould - be set to: + CONFIG_ARCH - Identifies the arch/ subdirectory. This sould + be set to: - CONFIG_ARCH=arm + CONFIG_ARCH=arm - CONFIG_ARCH_family - For use in C code: + CONFIG_ARCH_family - For use in C code: - CONFIG_ARCH_ARM=y + CONFIG_ARCH_ARM=y - CONFIG_ARCH_architecture - For use in C code: + CONFIG_ARCH_architecture - For use in C code: - CONFIG_ARCH_CORTEXM4=y + CONFIG_ARCH_CORTEXM4=y - CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory + CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory - CONFIG_ARCH_CHIP=k40 + CONFIG_ARCH_CHIP=k40 - CONFIG_ARCH_CHIP_name - For use in C code to identify the exact - chip: + CONFIG_ARCH_CHIP_name - For use in C code to identify the exact + chip: - CONFIG_ARCH_CHIP_MK60N512VMD100 + CONFIG_ARCH_CHIP_MK60N512VMD100 - CONFIG_ARCH_BOARD - Identifies the configs subdirectory and - hence, the board that supports the particular chip or SoC. + CONFIG_ARCH_BOARD - Identifies the configs subdirectory and + hence, the board that supports the particular chip or SoC. - CONFIG_ARCH_BOARD=twr-k60n512 (for the TWR-K60N512 development board) + CONFIG_ARCH_BOARD=twr-k60n512 (for the TWR-K60N512 development board) - CONFIG_ARCH_BOARD_name - For use in C code + CONFIG_ARCH_BOARD_name - For use in C code - CONFIG_ARCH_BOARD_TWR_K60N512=y + CONFIG_ARCH_BOARD_TWR_K60N512=y - CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation - of delay loops + CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation + of delay loops - CONFIG_ENDIAN_BIG - define if big endian (default is little - endian) + CONFIG_ENDIAN_BIG - define if big endian (default is little + endian) - CONFIG_DRAM_SIZE - Describes the installed DRAM (SRAM in this case): + CONFIG_DRAM_SIZE - Describes the installed DRAM (SRAM in this case): - CONFIG_DRAM_SIZE=0x00010000 (64Kb) + CONFIG_DRAM_SIZE=0x00010000 (64Kb) - CONFIG_DRAM_START - The start address of installed DRAM + CONFIG_DRAM_START - The start address of installed DRAM - CONFIG_DRAM_START=0x20000000 + CONFIG_DRAM_START=0x20000000 - CONFIG_ARCH_IRQPRIO - The Kinetis K60 supports interrupt prioritization + CONFIG_ARCH_IRQPRIO - The Kinetis K60 supports interrupt prioritization - CONFIG_ARCH_IRQPRIO=y + CONFIG_ARCH_IRQPRIO=y - CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that - have LEDs + CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that + have LEDs - CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt - stack. If defined, this symbol is the size of the interrupt - stack in bytes. If not defined, the user task stacks will be - used during interrupt handling. + CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt + stack. If defined, this symbol is the size of the interrupt + stack in bytes. If not defined, the user task stacks will be + used during interrupt handling. - CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions + CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions - CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. + CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. - CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that - cause a 100 second delay during boot-up. This 100 second delay - serves no purpose other than it allows you to calibratre - CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure - the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until - the delay actually is 100 seconds. + CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that + cause a 100 second delay during boot-up. This 100 second delay + serves no purpose other than it allows you to calibratre + CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure + the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until + the delay actually is 100 seconds. Individual subsystems can be enabled: CONFIG_KINETIS_TRACE -- Enable trace clocking on power up. CONFIG_KINETIS_FLEXBUS -- Enable flexbus clocking on power up. - CONFIG_KINETIS_UART0 -- Support UART0 - CONFIG_KINETIS_UART1 -- Support UART1 - CONFIG_KINETIS_UART2 -- Support UART2 - CONFIG_KINETIS_UART3 -- Support UART3 - CONFIG_KINETIS_UART4 -- Support UART4 - CONFIG_KINETIS_UART5 -- Support UART5 - CONFIG_KINETIS_ENET -- Support Ethernet (K60 only) - CONFIG_KINETIS_RNGB -- Support the random number generator(K60 only) + CONFIG_KINETIS_UART0 -- Support UART0 + CONFIG_KINETIS_UART1 -- Support UART1 + CONFIG_KINETIS_UART2 -- Support UART2 + CONFIG_KINETIS_UART3 -- Support UART3 + CONFIG_KINETIS_UART4 -- Support UART4 + CONFIG_KINETIS_UART5 -- Support UART5 + CONFIG_KINETIS_ENET -- Support Ethernet (K60 only) + CONFIG_KINETIS_RNGB -- Support the random number generator(K60 only) CONFIG_KINETIS_FLEXCAN0 -- Support FlexCAN0 CONFIG_KINETIS_FLEXCAN1 -- Support FlexCAN1 CONFIG_KINETIS_SPI0 -- Support SPI0 @@ -517,8 +568,8 @@ TWR-K60N512-specific Configuration Options CONFIG_KINETIS_I2C0 -- Support I2C0 CONFIG_KINETIS_I2C1 -- Support I2C1 CONFIG_KINETIS_I2S -- Support I2S - CONFIG_KINETIS_DAC0 -- Support DAC0 - CONFIG_KINETIS_DAC1 -- Support DAC1 + CONFIG_KINETIS_DAC0 -- Support DAC0 + CONFIG_KINETIS_DAC1 -- Support DAC1 CONFIG_KINETIS_ADC0 -- Support ADC0 CONFIG_KINETIS_ADC1 -- Support ADC1 CONFIG_KINETIS_CMP -- Support CMP @@ -571,15 +622,15 @@ TWR-K60N512-specific Configuration Options Kinetis K60 specific device driver settings - CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn (n=0..5) for the + CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn (n=0..5) for the console and ttys0 (default is the UART0). - CONFIG_UARTn_RXBUFSIZE - Characters are buffered as received. - This specific the size of the receive buffer - CONFIG_UARTn_TXBUFSIZE - Characters are buffered before - being sent. This specific the size of the transmit buffer - CONFIG_UARTn_BAUD - The configure BAUD of the UART. - CONFIG_UARTn_BITS - The number of bits. Must be either 8 or 8. - CONFIG_UARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity + CONFIG_UARTn_RXBUFSIZE - Characters are buffered as received. + This specific the size of the receive buffer + CONFIG_UARTn_TXBUFSIZE - Characters are buffered before + being sent. This specific the size of the transmit buffer + CONFIG_UARTn_BAUD - The configure BAUD of the UART. + CONFIG_UARTn_BITS - The number of bits. Must be either 8 or 8. + CONFIG_UARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity Kenetis ethernet controller settings @@ -596,10 +647,10 @@ Configurations Each TWR-K60N512 configuration is maintained in a sudirectory and can be selected as follow: - cd tools - ./configure.sh twr-k60n512/ - cd - - . ./setenv.sh + cd tools + ./configure.sh twr-k60n512/ + cd - + . ./setenv.sh Where is one of the following: @@ -609,7 +660,7 @@ Where is one of the following: examples/ostest. By default, this project assumes that you are using the DFU bootloader. - CONFIG_KINETIS_BUILDROOT=y : NuttX buildroot under Linux or Cygwin + CONFIG_KINETIS_BUILDROOT=y : NuttX buildroot under Linux or Cygwin nsh: --- @@ -618,7 +669,7 @@ Where is one of the following: Support for the board's SPI-based MicroSD card is included (but not passing tests as of this writing). - NOTE: An SDHC driver is underwork and can be enabled in the NSH + NOTE: An SDHC driver is underwork and can be enabled in the NSH configuration for further testing be setting the following configuration faluesas follows: diff --git a/nuttx/configs/vsn/README.txt b/nuttx/configs/vsn/README.txt index 0a8b02dbc..b05ffa5dd 100644 --- a/nuttx/configs/vsn/README.txt +++ b/nuttx/configs/vsn/README.txt @@ -11,7 +11,9 @@ Contents - Development Environment - GNU Toolchain Options - IDEs - - NuttX buildroot Toolchain + - NuttX EABI "buildroot" Toolchain + - NuttX OABI "buildroot" Toolchain + - NXFLAT Toolchain - DFU - LEDs - VSN-specific Configuration Options @@ -47,7 +49,7 @@ GNU Toolchain Options CONFIG_STM32_CODESOURCERYL=y : CodeSourcery under Linux 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_STM32_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default) If you are not using CONFIG_STM32_BUILDROOT, then you may also have to modify the PATH in the setenv.h file if your make cannot find the tools. @@ -128,8 +130,8 @@ IDEs one time from the Cygwin command line in order to obtain the pre-built startup object needed by RIDE. -NuttX buildroot Toolchain -^^^^^^^^^^^^^^^^^^^^^^^^^ +NuttX EABI "buildroot" Toolchain +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ A GNU GCC-based toolchain is assumed. The files */setenv.sh should be modified to point to the correct path to the Cortex-M3 GCC toolchain (if @@ -152,7 +154,7 @@ NuttX buildroot Toolchain 4. cd /buildroot - 5. cp configs/cortexm3-defconfig-4.3.3 .config + 5. cp configs/cortexm3-eabi-defconfig-4.6.3 .config 6. make oldconfig @@ -162,77 +164,126 @@ NuttX buildroot Toolchain the path to the newly built binaries. See the file configs/README.txt in the buildroot source tree. That has more - detailed PLUS some special instructions that you will need to follow if you are + details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. +NuttX OABI "buildroot" Toolchain +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + + The older, OABI buildroot toolchain is also available. To use the OABI + toolchain: + + 1. When building the buildroot toolchain, either (1) modify the cortexm3-eabi-defconfig-4.6.3 + configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI + configuration such as cortexm3-defconfig-4.3.3 + + 2. Modify the Make.defs file to use the OABI converntions: + + +CROSSDEV = arm-nuttx-elf- + +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + -CROSSDEV = arm-nuttx-eabi- + -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + +NXFLAT Toolchain +^^^^^^^^^^^^^^^^ + + If you are *not* using the NuttX buildroot toolchain and you want to use + the NXFLAT tools, then you will still have to build a portion of the buildroot + tools -- just the NXFLAT tools. The buildroot with the NXFLAT tools can + be downloaded from the NuttX SourceForge download site + (https://sourceforge.net/projects/nuttx/files/). + + This GNU toolchain builds and executes in the Linux or Cygwin environment. + + 1. You must have already configured Nuttx in /nuttx. + + cd tools + ./configure.sh lpcxpresso-lpc1768/ + + 2. Download the latest buildroot package into + + 3. unpack the buildroot tarball. The resulting directory may + have versioning information on it like buildroot-x.y.z. If so, + rename /buildroot-x.y.z to /buildroot. + + 4. cd /buildroot + + 5. cp configs/cortexm3-defconfig-nxflat .config + + 6. make oldconfig + + 7. make + + 8. Edit setenv.h, if necessary, so that the PATH variable includes + the path to the newly builtNXFLAT binaries. VSN-specific Configuration Options ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - CONFIG_ARCH - Identifies the arch/ subdirectory. This should - be set to: + CONFIG_ARCH - Identifies the arch/ subdirectory. This should + be set to: - CONFIG_ARCH=arm + CONFIG_ARCH=arm - CONFIG_ARCH_family - For use in C code: + CONFIG_ARCH_family - For use in C code: - CONFIG_ARCH_ARM=y + CONFIG_ARCH_ARM=y - CONFIG_ARCH_architecture - For use in C code: + CONFIG_ARCH_architecture - For use in C code: - CONFIG_ARCH_CORTEXM3=y + CONFIG_ARCH_CORTEXM3=y - CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory + CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory - CONFIG_ARCH_CHIP=stm32 + CONFIG_ARCH_CHIP=stm32 - CONFIG_ARCH_CHIP_name - For use in C code to identify the exact - chip: + CONFIG_ARCH_CHIP_name - For use in C code to identify the exact + chip: - CONFIG_ARCH_CHIP_STM32F103RET6 + CONFIG_ARCH_CHIP_STM32F103RET6 - CONFIG_ARCH_BOARD - Identifies the configs subdirectory and - hence, the board that supports the particular chip or SoC. + CONFIG_ARCH_BOARD - Identifies the configs subdirectory and + hence, the board that supports the particular chip or SoC. - CONFIG_ARCH_BOARD=vsn (for the VSN development board) + CONFIG_ARCH_BOARD=vsn (for the VSN development board) - CONFIG_ARCH_BOARD_name - For use in C code - - CONFIG_ARCH_BOARD_VSN=y + CONFIG_ARCH_BOARD_name - For use in C code + + CONFIG_ARCH_BOARD_VSN=y - CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation - of delay loops + CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation + of delay loops - CONFIG_ENDIAN_BIG - define if big endian (default is little - endian) + CONFIG_ENDIAN_BIG - define if big endian (default is little + endian) - CONFIG_DRAM_SIZE - Describes the installed DRAM (SRAM in this case): + CONFIG_DRAM_SIZE - Describes the installed DRAM (SRAM in this case): - CONFIG_DRAM_SIZE=0x00010000 (64Kb) + CONFIG_DRAM_SIZE=0x00010000 (64Kb) - CONFIG_DRAM_START - The start address of installed DRAM + CONFIG_DRAM_START - The start address of installed DRAM - CONFIG_DRAM_START=0x20000000 + CONFIG_DRAM_START=0x20000000 - CONFIG_ARCH_IRQPRIO - The STM32F103Z supports interrupt prioritization + CONFIG_ARCH_IRQPRIO - The STM32F103Z supports interrupt prioritization - CONFIG_ARCH_IRQPRIO=y + CONFIG_ARCH_IRQPRIO=y - CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt - stack. If defined, this symbol is the size of the interrupt - stack in bytes. If not defined, the user task stacks will be - used during interrupt handling. + CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt + stack. If defined, this symbol is the size of the interrupt + stack in bytes. If not defined, the user task stacks will be + used during interrupt handling. - CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions + CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions - CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. + CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. - CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that - cause a 100 second delay during boot-up. This 100 second delay - serves no purpose other than it allows you to calibratre - CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure - the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until - the delay actually is 100 seconds. + CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that + cause a 100 second delay during boot-up. This 100 second delay + serves no purpose other than it allows you to calibratre + CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure + the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until + the delay actually is 100 seconds. Configurations @@ -241,10 +292,10 @@ Configurations Each VSN configuration is maintained in a sudirectory and can be selected as follow: - cd tools - ./configure.sh vsn/ - cd - - . ./setenv.sh + cd tools + ./configure.sh vsn/ + cd - + . ./setenv.sh Where is one of the following: -- cgit v1.2.3 From ee341514da6ef18f2dca79226e5221268d49f4d2 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 6 Oct 2012 18:09:05 +0000 Subject: All Cortex-M Make.defs files updated to use buildroot EABI toolchain if BUILDROOT=y selected git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5219 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/configs/ekk-lm3s9b96/nsh/Make.defs | 8 ++++++-- nuttx/configs/ekk-lm3s9b96/ostest/Make.defs | 8 ++++++-- nuttx/configs/fire-stm32v2/nsh/Make.defs | 9 ++++++++- nuttx/configs/hymini-stm32v/buttons/Make.defs | 8 ++++++-- nuttx/configs/hymini-stm32v/nsh/Make.defs | 8 ++++++-- nuttx/configs/hymini-stm32v/nsh2/Make.defs | 8 ++++++-- nuttx/configs/hymini-stm32v/nx/Make.defs | 8 ++++++-- nuttx/configs/hymini-stm32v/nxlines/Make.defs | 8 ++++++-- nuttx/configs/hymini-stm32v/usbserial/Make.defs | 8 ++++++-- nuttx/configs/hymini-stm32v/usbstorage/Make.defs | 8 ++++++-- nuttx/configs/kwikstik-k40/ostest/Make.defs | 8 ++++++-- nuttx/configs/lincoln60/nsh/Make.defs | 8 ++++++-- nuttx/configs/lincoln60/ostest/Make.defs | 8 ++++++-- nuttx/configs/lm3s6432-s2e/nsh/Make.defs | 8 ++++++-- nuttx/configs/lm3s6432-s2e/ostest/Make.defs | 8 ++++++-- nuttx/configs/lm3s6965-ek/nsh/Make.defs | 8 ++++++-- nuttx/configs/lm3s6965-ek/nx/Make.defs | 8 ++++++-- nuttx/configs/lm3s6965-ek/ostest/Make.defs | 8 ++++++-- nuttx/configs/lm3s8962-ek/nsh/Make.defs | 8 ++++++-- nuttx/configs/lm3s8962-ek/nx/Make.defs | 8 ++++++-- nuttx/configs/lm3s8962-ek/ostest/Make.defs | 8 ++++++-- nuttx/configs/lpc4330-xplorer/nsh/Make.defs | 11 ++++++++--- nuttx/configs/lpc4330-xplorer/ostest/Make.defs | 11 ++++++++--- nuttx/configs/lpcxpresso-lpc1768/dhcpd/Make.defs | 8 ++++++-- nuttx/configs/lpcxpresso-lpc1768/nsh/Make.defs | 8 ++++++-- nuttx/configs/lpcxpresso-lpc1768/nx/Make.defs | 8 ++++++-- nuttx/configs/lpcxpresso-lpc1768/ostest/Make.defs | 8 ++++++-- nuttx/configs/lpcxpresso-lpc1768/thttpd/Make.defs | 8 ++++++-- nuttx/configs/lpcxpresso-lpc1768/usbstorage/Make.defs | 8 ++++++-- nuttx/configs/mbed/hidkbd/Make.defs | 8 ++++++-- nuttx/configs/mbed/nsh/Make.defs | 8 ++++++-- nuttx/configs/nucleus2g/nsh/Make.defs | 8 ++++++-- nuttx/configs/nucleus2g/ostest/Make.defs | 8 ++++++-- nuttx/configs/nucleus2g/usbserial/Make.defs | 8 ++++++-- nuttx/configs/nucleus2g/usbstorage/Make.defs | 8 ++++++-- nuttx/configs/olimex-lpc1766stk/ftpc/Make.defs | 8 ++++++-- nuttx/configs/olimex-lpc1766stk/hidkbd/Make.defs | 8 ++++++-- nuttx/configs/olimex-lpc1766stk/nettest/Make.defs | 8 ++++++-- nuttx/configs/olimex-lpc1766stk/nsh/Make.defs | 8 ++++++-- nuttx/configs/olimex-lpc1766stk/nx/Make.defs | 8 ++++++-- nuttx/configs/olimex-lpc1766stk/ostest/Make.defs | 8 ++++++-- nuttx/configs/olimex-lpc1766stk/slip-httpd/Make.defs | 8 ++++++-- nuttx/configs/olimex-lpc1766stk/thttpd/Make.defs | 8 ++++++-- nuttx/configs/olimex-lpc1766stk/usbserial/Make.defs | 8 ++++++-- nuttx/configs/olimex-lpc1766stk/usbstorage/Make.defs | 8 ++++++-- nuttx/configs/olimex-lpc1766stk/wlan/Make.defs | 8 ++++++-- nuttx/configs/olimex-stm32-p107/nsh/Make.defs | 8 ++++++-- nuttx/configs/olimex-stm32-p107/ostest/Make.defs | 8 ++++++-- nuttx/configs/sam3u-ek/knsh/Make.defs | 8 ++++++-- nuttx/configs/sam3u-ek/nsh/Make.defs | 8 ++++++-- nuttx/configs/sam3u-ek/nx/Make.defs | 8 ++++++-- nuttx/configs/sam3u-ek/ostest/Make.defs | 8 ++++++-- nuttx/configs/sam3u-ek/touchscreen/Make.defs | 8 ++++++-- nuttx/configs/shenzhou/nsh/Make.defs | 6 +++++- nuttx/configs/shenzhou/nxwm/Make.defs | 6 +++++- nuttx/configs/stm3210e-eval/RIDE/Make.defs | 8 ++++++-- nuttx/configs/stm3210e-eval/buttons/Make.defs | 8 ++++++-- nuttx/configs/stm3210e-eval/composite/Make.defs | 8 ++++++-- nuttx/configs/stm3210e-eval/nsh/Make.defs | 8 ++++++-- nuttx/configs/stm3210e-eval/nsh2/Make.defs | 8 ++++++-- nuttx/configs/stm3210e-eval/nx/Make.defs | 8 ++++++-- nuttx/configs/stm3210e-eval/nxconsole/Make.defs | 8 ++++++-- nuttx/configs/stm3210e-eval/nxlines/Make.defs | 8 ++++++-- nuttx/configs/stm3210e-eval/nxtext/Make.defs | 8 ++++++-- nuttx/configs/stm3210e-eval/ostest/Make.defs | 8 ++++++-- nuttx/configs/stm3210e-eval/pm/Make.defs | 8 ++++++-- nuttx/configs/stm3210e-eval/usbserial/Make.defs | 8 ++++++-- nuttx/configs/stm3210e-eval/usbstorage/Make.defs | 8 ++++++-- nuttx/configs/stm3220g-eval/dhcpd/Make.defs | 11 ++++++++--- nuttx/configs/stm3220g-eval/nettest/Make.defs | 11 ++++++++--- nuttx/configs/stm3220g-eval/nsh/Make.defs | 11 ++++++++--- nuttx/configs/stm3220g-eval/nsh2/Make.defs | 11 ++++++++--- nuttx/configs/stm3220g-eval/nxwm/Make.defs | 11 ++++++++--- nuttx/configs/stm3220g-eval/ostest/Make.defs | 11 ++++++++--- nuttx/configs/stm3220g-eval/telnetd/Make.defs | 11 ++++++++--- nuttx/configs/stm3240g-eval/dhcpd/Make.defs | 11 ++++++++--- nuttx/configs/stm3240g-eval/discover/Make.defs | 11 ++++++++--- nuttx/configs/stm3240g-eval/nettest/Make.defs | 11 ++++++++--- nuttx/configs/stm3240g-eval/nsh/Make.defs | 11 ++++++++--- nuttx/configs/stm3240g-eval/nsh2/Make.defs | 11 ++++++++--- nuttx/configs/stm3240g-eval/nxconsole/Make.defs | 11 ++++++++--- nuttx/configs/stm3240g-eval/nxwm/Make.defs | 11 ++++++++--- nuttx/configs/stm3240g-eval/ostest/Make.defs | 11 ++++++++--- nuttx/configs/stm3240g-eval/telnetd/Make.defs | 11 ++++++++--- nuttx/configs/stm3240g-eval/webserver/Make.defs | 11 ++++++++--- nuttx/configs/stm3240g-eval/xmlrpc/Make.defs | 11 ++++++++--- nuttx/configs/stm32f4discovery/nsh/Make.defs | 11 ++++++++--- nuttx/configs/stm32f4discovery/nxlines/Make.defs | 11 ++++++++--- nuttx/configs/stm32f4discovery/ostest/Make.defs | 11 ++++++++--- nuttx/configs/stm32f4discovery/pm/Make.defs | 11 ++++++++--- nuttx/configs/twr-k60n512/nsh/Make.defs | 8 ++++++-- nuttx/configs/twr-k60n512/ostest/Make.defs | 8 ++++++-- nuttx/configs/vsn/nsh/Make.defs | 8 ++++++-- 93 files changed, 606 insertions(+), 207 deletions(-) (limited to 'nuttx') diff --git a/nuttx/configs/ekk-lm3s9b96/nsh/Make.defs b/nuttx/configs/ekk-lm3s9b96/nsh/Make.defs index 1be7fc8f0..e810ec175 100644 --- a/nuttx/configs/ekk-lm3s9b96/nsh/Make.defs +++ b/nuttx/configs/ekk-lm3s9b96/nsh/Make.defs @@ -59,8 +59,12 @@ ifeq ($(CONFIG_LM3S_DEVKITARM),y) endif ifeq ($(CONFIG_LM3S_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/ekk-lm3s9b96/ostest/Make.defs b/nuttx/configs/ekk-lm3s9b96/ostest/Make.defs index e0fae20f0..ca38be836 100644 --- a/nuttx/configs/ekk-lm3s9b96/ostest/Make.defs +++ b/nuttx/configs/ekk-lm3s9b96/ostest/Make.defs @@ -59,8 +59,12 @@ ifeq ($(CONFIG_LM3S_DEVKITARM),y) endif ifeq ($(CONFIG_LM3S_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/fire-stm32v2/nsh/Make.defs b/nuttx/configs/fire-stm32v2/nsh/Make.defs index aaf0e8980..f64dda4d2 100644 --- a/nuttx/configs/fire-stm32v2/nsh/Make.defs +++ b/nuttx/configs/fire-stm32v2/nsh/Make.defs @@ -83,8 +83,15 @@ endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin CROSSDEV = arm-nuttx-elf- - ARCROSSDEV = arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/hymini-stm32v/buttons/Make.defs b/nuttx/configs/hymini-stm32v/buttons/Make.defs index bcc1f6845..eb121c2cb 100644 --- a/nuttx/configs/hymini-stm32v/buttons/Make.defs +++ b/nuttx/configs/hymini-stm32v/buttons/Make.defs @@ -70,8 +70,12 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/hymini-stm32v/nsh/Make.defs b/nuttx/configs/hymini-stm32v/nsh/Make.defs index fae6edc08..a0809f98a 100644 --- a/nuttx/configs/hymini-stm32v/nsh/Make.defs +++ b/nuttx/configs/hymini-stm32v/nsh/Make.defs @@ -70,8 +70,12 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/hymini-stm32v/nsh2/Make.defs b/nuttx/configs/hymini-stm32v/nsh2/Make.defs index 1cf89238e..72960ee27 100644 --- a/nuttx/configs/hymini-stm32v/nsh2/Make.defs +++ b/nuttx/configs/hymini-stm32v/nsh2/Make.defs @@ -70,8 +70,12 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/hymini-stm32v/nx/Make.defs b/nuttx/configs/hymini-stm32v/nx/Make.defs index 8ebded094..d647c7fcd 100644 --- a/nuttx/configs/hymini-stm32v/nx/Make.defs +++ b/nuttx/configs/hymini-stm32v/nx/Make.defs @@ -70,8 +70,12 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/hymini-stm32v/nxlines/Make.defs b/nuttx/configs/hymini-stm32v/nxlines/Make.defs index 15521d621..fa66e6be0 100644 --- a/nuttx/configs/hymini-stm32v/nxlines/Make.defs +++ b/nuttx/configs/hymini-stm32v/nxlines/Make.defs @@ -73,8 +73,12 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/hymini-stm32v/usbserial/Make.defs b/nuttx/configs/hymini-stm32v/usbserial/Make.defs index b58c4c1fe..d0a2a80cc 100644 --- a/nuttx/configs/hymini-stm32v/usbserial/Make.defs +++ b/nuttx/configs/hymini-stm32v/usbserial/Make.defs @@ -70,8 +70,12 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/hymini-stm32v/usbstorage/Make.defs b/nuttx/configs/hymini-stm32v/usbstorage/Make.defs index f3264ab93..ee870eab4 100644 --- a/nuttx/configs/hymini-stm32v/usbstorage/Make.defs +++ b/nuttx/configs/hymini-stm32v/usbstorage/Make.defs @@ -70,8 +70,12 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/kwikstik-k40/ostest/Make.defs b/nuttx/configs/kwikstik-k40/ostest/Make.defs index 43a5dd01e..beba9e397 100644 --- a/nuttx/configs/kwikstik-k40/ostest/Make.defs +++ b/nuttx/configs/kwikstik-k40/ostest/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_KINETIS_DEVKITARM),y) endif ifeq ($(CONFIG_KINETIS_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft -mlong-calls + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/lincoln60/nsh/Make.defs b/nuttx/configs/lincoln60/nsh/Make.defs index 9750a0e87..7b3c3318a 100644 --- a/nuttx/configs/lincoln60/nsh/Make.defs +++ b/nuttx/configs/lincoln60/nsh/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/lincoln60/ostest/Make.defs b/nuttx/configs/lincoln60/ostest/Make.defs index c90939429..bd4b25701 100644 --- a/nuttx/configs/lincoln60/ostest/Make.defs +++ b/nuttx/configs/lincoln60/ostest/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/lm3s6432-s2e/nsh/Make.defs b/nuttx/configs/lm3s6432-s2e/nsh/Make.defs index ef39674b2..e463a1742 100644 --- a/nuttx/configs/lm3s6432-s2e/nsh/Make.defs +++ b/nuttx/configs/lm3s6432-s2e/nsh/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LM3S_DEVKITARM),y) endif ifeq ($(CONFIG_LM3S_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/lm3s6432-s2e/ostest/Make.defs b/nuttx/configs/lm3s6432-s2e/ostest/Make.defs index 603689183..33f0d43ed 100644 --- a/nuttx/configs/lm3s6432-s2e/ostest/Make.defs +++ b/nuttx/configs/lm3s6432-s2e/ostest/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LM3S_DEVKITARM),y) endif ifeq ($(CONFIG_LM3S_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/lm3s6965-ek/nsh/Make.defs b/nuttx/configs/lm3s6965-ek/nsh/Make.defs index 17df0ebf7..5aaed9009 100644 --- a/nuttx/configs/lm3s6965-ek/nsh/Make.defs +++ b/nuttx/configs/lm3s6965-ek/nsh/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LM3S_DEVKITARM),y) endif ifeq ($(CONFIG_LM3S_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/lm3s6965-ek/nx/Make.defs b/nuttx/configs/lm3s6965-ek/nx/Make.defs index 5ab0cfd26..8b99d7de7 100644 --- a/nuttx/configs/lm3s6965-ek/nx/Make.defs +++ b/nuttx/configs/lm3s6965-ek/nx/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LM3S_DEVKITARM),y) endif ifeq ($(CONFIG_LM3S_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/lm3s6965-ek/ostest/Make.defs b/nuttx/configs/lm3s6965-ek/ostest/Make.defs index 5e49273a0..434b21e24 100644 --- a/nuttx/configs/lm3s6965-ek/ostest/Make.defs +++ b/nuttx/configs/lm3s6965-ek/ostest/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LM3S_DEVKITARM),y) endif ifeq ($(CONFIG_LM3S_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/lm3s8962-ek/nsh/Make.defs b/nuttx/configs/lm3s8962-ek/nsh/Make.defs index cc7bce1e5..d7be642cd 100644 --- a/nuttx/configs/lm3s8962-ek/nsh/Make.defs +++ b/nuttx/configs/lm3s8962-ek/nsh/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LM3S_DEVKITARM),y) endif ifeq ($(CONFIG_LM3S_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/lm3s8962-ek/nx/Make.defs b/nuttx/configs/lm3s8962-ek/nx/Make.defs index b97aaa31e..bf07df29a 100644 --- a/nuttx/configs/lm3s8962-ek/nx/Make.defs +++ b/nuttx/configs/lm3s8962-ek/nx/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LM3S_DEVKITARM),y) endif ifeq ($(CONFIG_LM3S_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/lm3s8962-ek/ostest/Make.defs b/nuttx/configs/lm3s8962-ek/ostest/Make.defs index 4b4863d7c..94389216c 100644 --- a/nuttx/configs/lm3s8962-ek/ostest/Make.defs +++ b/nuttx/configs/lm3s8962-ek/ostest/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LM3S_DEVKITARM),y) endif ifeq ($(CONFIG_LM3S_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/lpc4330-xplorer/nsh/Make.defs b/nuttx/configs/lpc4330-xplorer/nsh/Make.defs index 960fb2a41..757759ecc 100644 --- a/nuttx/configs/lpc4330-xplorer/nsh/Make.defs +++ b/nuttx/configs/lpc4330-xplorer/nsh/Make.defs @@ -93,9 +93,14 @@ ifeq ($(CONFIG_LPC43_DEVKITARM),y) endif ifeq ($(CONFIG_LPC43_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m4 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/lpc4330-xplorer/ostest/Make.defs b/nuttx/configs/lpc4330-xplorer/ostest/Make.defs index 960fb2a41..757759ecc 100644 --- a/nuttx/configs/lpc4330-xplorer/ostest/Make.defs +++ b/nuttx/configs/lpc4330-xplorer/ostest/Make.defs @@ -93,9 +93,14 @@ ifeq ($(CONFIG_LPC43_DEVKITARM),y) endif ifeq ($(CONFIG_LPC43_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m4 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/lpcxpresso-lpc1768/dhcpd/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/dhcpd/Make.defs index 804e20ecd..15109a1ad 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/dhcpd/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/dhcpd/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif ifeq ($(CONFIG_LPC17_CODEREDW),y) diff --git a/nuttx/configs/lpcxpresso-lpc1768/nsh/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/nsh/Make.defs index 8c6ad9ab8..b29d10982 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/nsh/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/nsh/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif ifeq ($(CONFIG_LPC17_CODEREDW),y) diff --git a/nuttx/configs/lpcxpresso-lpc1768/nx/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/nx/Make.defs index a535fd03d..31286436a 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/nx/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/nx/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif ifeq ($(CONFIG_LPC17_CODEREDW),y) diff --git a/nuttx/configs/lpcxpresso-lpc1768/ostest/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/ostest/Make.defs index 1b38f2d6b..975cdf460 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/ostest/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/ostest/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif ifeq ($(CONFIG_LPC17_CODEREDW),y) diff --git a/nuttx/configs/lpcxpresso-lpc1768/thttpd/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/thttpd/Make.defs index 810d6d7da..67534a5c1 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/thttpd/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/thttpd/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif ifeq ($(CONFIG_LPC17_CODEREDW),y) diff --git a/nuttx/configs/lpcxpresso-lpc1768/usbstorage/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/usbstorage/Make.defs index 5342dde5b..087a92287 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/usbstorage/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/usbstorage/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif ifeq ($(CONFIG_LPC17_CODEREDW),y) diff --git a/nuttx/configs/mbed/hidkbd/Make.defs b/nuttx/configs/mbed/hidkbd/Make.defs index 262571e45..043340da1 100644 --- a/nuttx/configs/mbed/hidkbd/Make.defs +++ b/nuttx/configs/mbed/hidkbd/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/mbed/nsh/Make.defs b/nuttx/configs/mbed/nsh/Make.defs index 40c4c94f3..549178e9c 100644 --- a/nuttx/configs/mbed/nsh/Make.defs +++ b/nuttx/configs/mbed/nsh/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/nucleus2g/nsh/Make.defs b/nuttx/configs/nucleus2g/nsh/Make.defs index 3b8f857a6..e21f7f1c8 100644 --- a/nuttx/configs/nucleus2g/nsh/Make.defs +++ b/nuttx/configs/nucleus2g/nsh/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/nucleus2g/ostest/Make.defs b/nuttx/configs/nucleus2g/ostest/Make.defs index aa0e6f864..5696eae22 100644 --- a/nuttx/configs/nucleus2g/ostest/Make.defs +++ b/nuttx/configs/nucleus2g/ostest/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/nucleus2g/usbserial/Make.defs b/nuttx/configs/nucleus2g/usbserial/Make.defs index 483fd5260..2cdccc959 100644 --- a/nuttx/configs/nucleus2g/usbserial/Make.defs +++ b/nuttx/configs/nucleus2g/usbserial/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/nucleus2g/usbstorage/Make.defs b/nuttx/configs/nucleus2g/usbstorage/Make.defs index 7a9c1fa6b..79f1b8c1f 100644 --- a/nuttx/configs/nucleus2g/usbstorage/Make.defs +++ b/nuttx/configs/nucleus2g/usbstorage/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/olimex-lpc1766stk/ftpc/Make.defs b/nuttx/configs/olimex-lpc1766stk/ftpc/Make.defs index 5671fdffb..fb8d55023 100644 --- a/nuttx/configs/olimex-lpc1766stk/ftpc/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/ftpc/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/olimex-lpc1766stk/hidkbd/Make.defs b/nuttx/configs/olimex-lpc1766stk/hidkbd/Make.defs index 1e7160c38..1997d66b3 100644 --- a/nuttx/configs/olimex-lpc1766stk/hidkbd/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/hidkbd/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/olimex-lpc1766stk/nettest/Make.defs b/nuttx/configs/olimex-lpc1766stk/nettest/Make.defs index 2502cf97b..203662941 100644 --- a/nuttx/configs/olimex-lpc1766stk/nettest/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/nettest/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/olimex-lpc1766stk/nsh/Make.defs b/nuttx/configs/olimex-lpc1766stk/nsh/Make.defs index 7e62fd7fb..7110759ba 100644 --- a/nuttx/configs/olimex-lpc1766stk/nsh/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/nsh/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/olimex-lpc1766stk/nx/Make.defs b/nuttx/configs/olimex-lpc1766stk/nx/Make.defs index 735e2bd0a..e8325f780 100644 --- a/nuttx/configs/olimex-lpc1766stk/nx/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/nx/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/olimex-lpc1766stk/ostest/Make.defs b/nuttx/configs/olimex-lpc1766stk/ostest/Make.defs index 7a9475761..f7775e072 100644 --- a/nuttx/configs/olimex-lpc1766stk/ostest/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/ostest/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/olimex-lpc1766stk/slip-httpd/Make.defs b/nuttx/configs/olimex-lpc1766stk/slip-httpd/Make.defs index 35d2c6480..7f7278d06 100644 --- a/nuttx/configs/olimex-lpc1766stk/slip-httpd/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/slip-httpd/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/olimex-lpc1766stk/thttpd/Make.defs b/nuttx/configs/olimex-lpc1766stk/thttpd/Make.defs index dbd84c2a6..96270bc28 100644 --- a/nuttx/configs/olimex-lpc1766stk/thttpd/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/thttpd/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/olimex-lpc1766stk/usbserial/Make.defs b/nuttx/configs/olimex-lpc1766stk/usbserial/Make.defs index 07cd41d46..2d7321efd 100644 --- a/nuttx/configs/olimex-lpc1766stk/usbserial/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/usbserial/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/olimex-lpc1766stk/usbstorage/Make.defs b/nuttx/configs/olimex-lpc1766stk/usbstorage/Make.defs index 76a6927ee..8c62990ae 100644 --- a/nuttx/configs/olimex-lpc1766stk/usbstorage/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/usbstorage/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/olimex-lpc1766stk/wlan/Make.defs b/nuttx/configs/olimex-lpc1766stk/wlan/Make.defs index 0cc0d7edd..593d5f939 100644 --- a/nuttx/configs/olimex-lpc1766stk/wlan/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/wlan/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_LPC17_DEVKITARM),y) endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/olimex-stm32-p107/nsh/Make.defs b/nuttx/configs/olimex-stm32-p107/nsh/Make.defs index 0108ef1ee..5175c2f8f 100644 --- a/nuttx/configs/olimex-stm32-p107/nsh/Make.defs +++ b/nuttx/configs/olimex-stm32-p107/nsh/Make.defs @@ -70,8 +70,12 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/olimex-stm32-p107/ostest/Make.defs b/nuttx/configs/olimex-stm32-p107/ostest/Make.defs index 7cf5e765f..28c9ab813 100644 --- a/nuttx/configs/olimex-stm32-p107/ostest/Make.defs +++ b/nuttx/configs/olimex-stm32-p107/ostest/Make.defs @@ -70,8 +70,12 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/sam3u-ek/knsh/Make.defs b/nuttx/configs/sam3u-ek/knsh/Make.defs index bbe8b23c0..f65420bcf 100644 --- a/nuttx/configs/sam3u-ek/knsh/Make.defs +++ b/nuttx/configs/sam3u-ek/knsh/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_SAM3U_DEVKITARM),y) endif ifeq ($(CONFIG_SAM3U_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/sam3u-ek/nsh/Make.defs b/nuttx/configs/sam3u-ek/nsh/Make.defs index 0f236114f..c73b1f785 100644 --- a/nuttx/configs/sam3u-ek/nsh/Make.defs +++ b/nuttx/configs/sam3u-ek/nsh/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_SAM3U_DEVKITARM),y) endif ifeq ($(CONFIG_SAM3U_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/sam3u-ek/nx/Make.defs b/nuttx/configs/sam3u-ek/nx/Make.defs index 10cabe5a5..31b440781 100644 --- a/nuttx/configs/sam3u-ek/nx/Make.defs +++ b/nuttx/configs/sam3u-ek/nx/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_SAM3U_DEVKITARM),y) endif ifeq ($(CONFIG_SAM3U_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/sam3u-ek/ostest/Make.defs b/nuttx/configs/sam3u-ek/ostest/Make.defs index 7689fb2a1..9fcea29f6 100644 --- a/nuttx/configs/sam3u-ek/ostest/Make.defs +++ b/nuttx/configs/sam3u-ek/ostest/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_SAM3U_DEVKITARM),y) endif ifeq ($(CONFIG_SAM3U_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/sam3u-ek/touchscreen/Make.defs b/nuttx/configs/sam3u-ek/touchscreen/Make.defs index 2047daf68..fb8ab9358 100644 --- a/nuttx/configs/sam3u-ek/touchscreen/Make.defs +++ b/nuttx/configs/sam3u-ek/touchscreen/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_SAM3U_DEVKITARM),y) endif ifeq ($(CONFIG_SAM3U_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/shenzhou/nsh/Make.defs b/nuttx/configs/shenzhou/nsh/Make.defs index 555b0069f..588bb2760 100644 --- a/nuttx/configs/shenzhou/nsh/Make.defs +++ b/nuttx/configs/shenzhou/nsh/Make.defs @@ -82,9 +82,13 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI CROSSDEV = arm-nuttx-eabi- ARCROSSDEV = arm-nuttx-eabi- -# ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/shenzhou/nxwm/Make.defs b/nuttx/configs/shenzhou/nxwm/Make.defs index dfb0472a1..d94f0c38a 100644 --- a/nuttx/configs/shenzhou/nxwm/Make.defs +++ b/nuttx/configs/shenzhou/nxwm/Make.defs @@ -82,9 +82,13 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI CROSSDEV = arm-nuttx-eabi- ARCROSSDEV = arm-nuttx-eabi- -# ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm3210e-eval/RIDE/Make.defs b/nuttx/configs/stm3210e-eval/RIDE/Make.defs index dfd0f600b..30dfda704 100644 --- a/nuttx/configs/stm3210e-eval/RIDE/Make.defs +++ b/nuttx/configs/stm3210e-eval/RIDE/Make.defs @@ -70,8 +70,12 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm3210e-eval/buttons/Make.defs b/nuttx/configs/stm3210e-eval/buttons/Make.defs index 9f0691bba..f18619f80 100644 --- a/nuttx/configs/stm3210e-eval/buttons/Make.defs +++ b/nuttx/configs/stm3210e-eval/buttons/Make.defs @@ -70,8 +70,12 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm3210e-eval/composite/Make.defs b/nuttx/configs/stm3210e-eval/composite/Make.defs index 9b855671f..848663573 100644 --- a/nuttx/configs/stm3210e-eval/composite/Make.defs +++ b/nuttx/configs/stm3210e-eval/composite/Make.defs @@ -70,8 +70,12 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm3210e-eval/nsh/Make.defs b/nuttx/configs/stm3210e-eval/nsh/Make.defs index afdf0c097..e3e4888fe 100644 --- a/nuttx/configs/stm3210e-eval/nsh/Make.defs +++ b/nuttx/configs/stm3210e-eval/nsh/Make.defs @@ -70,8 +70,12 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm3210e-eval/nsh2/Make.defs b/nuttx/configs/stm3210e-eval/nsh2/Make.defs index 7d36c9a00..330516696 100644 --- a/nuttx/configs/stm3210e-eval/nsh2/Make.defs +++ b/nuttx/configs/stm3210e-eval/nsh2/Make.defs @@ -70,8 +70,12 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm3210e-eval/nx/Make.defs b/nuttx/configs/stm3210e-eval/nx/Make.defs index bb0ba5b6d..6aaa6644b 100644 --- a/nuttx/configs/stm3210e-eval/nx/Make.defs +++ b/nuttx/configs/stm3210e-eval/nx/Make.defs @@ -70,8 +70,12 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm3210e-eval/nxconsole/Make.defs b/nuttx/configs/stm3210e-eval/nxconsole/Make.defs index 84b36b267..7b2be02a5 100644 --- a/nuttx/configs/stm3210e-eval/nxconsole/Make.defs +++ b/nuttx/configs/stm3210e-eval/nxconsole/Make.defs @@ -73,8 +73,12 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm3210e-eval/nxlines/Make.defs b/nuttx/configs/stm3210e-eval/nxlines/Make.defs index a896a901e..1469658a0 100644 --- a/nuttx/configs/stm3210e-eval/nxlines/Make.defs +++ b/nuttx/configs/stm3210e-eval/nxlines/Make.defs @@ -73,8 +73,12 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm3210e-eval/nxtext/Make.defs b/nuttx/configs/stm3210e-eval/nxtext/Make.defs index 00370c3b0..b130e5622 100644 --- a/nuttx/configs/stm3210e-eval/nxtext/Make.defs +++ b/nuttx/configs/stm3210e-eval/nxtext/Make.defs @@ -73,8 +73,12 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm3210e-eval/ostest/Make.defs b/nuttx/configs/stm3210e-eval/ostest/Make.defs index 09b3f0395..bd50d3b69 100644 --- a/nuttx/configs/stm3210e-eval/ostest/Make.defs +++ b/nuttx/configs/stm3210e-eval/ostest/Make.defs @@ -70,8 +70,12 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm3210e-eval/pm/Make.defs b/nuttx/configs/stm3210e-eval/pm/Make.defs index 0cc96fa4e..6ad7e3a4c 100644 --- a/nuttx/configs/stm3210e-eval/pm/Make.defs +++ b/nuttx/configs/stm3210e-eval/pm/Make.defs @@ -70,8 +70,12 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm3210e-eval/usbserial/Make.defs b/nuttx/configs/stm3210e-eval/usbserial/Make.defs index cda6edf4e..586c361a9 100644 --- a/nuttx/configs/stm3210e-eval/usbserial/Make.defs +++ b/nuttx/configs/stm3210e-eval/usbserial/Make.defs @@ -70,8 +70,12 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm3210e-eval/usbstorage/Make.defs b/nuttx/configs/stm3210e-eval/usbstorage/Make.defs index 36688bc80..c305b42c9 100644 --- a/nuttx/configs/stm3210e-eval/usbstorage/Make.defs +++ b/nuttx/configs/stm3210e-eval/usbstorage/Make.defs @@ -70,8 +70,12 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm3220g-eval/dhcpd/Make.defs b/nuttx/configs/stm3220g-eval/dhcpd/Make.defs index f75e94501..3f2c4e066 100644 --- a/nuttx/configs/stm3220g-eval/dhcpd/Make.defs +++ b/nuttx/configs/stm3220g-eval/dhcpd/Make.defs @@ -90,9 +90,14 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm3220g-eval/nettest/Make.defs b/nuttx/configs/stm3220g-eval/nettest/Make.defs index f307d9475..c6b2f895b 100644 --- a/nuttx/configs/stm3220g-eval/nettest/Make.defs +++ b/nuttx/configs/stm3220g-eval/nettest/Make.defs @@ -90,9 +90,14 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm3220g-eval/nsh/Make.defs b/nuttx/configs/stm3220g-eval/nsh/Make.defs index 9fe8b0ffa..3bd7c1528 100644 --- a/nuttx/configs/stm3220g-eval/nsh/Make.defs +++ b/nuttx/configs/stm3220g-eval/nsh/Make.defs @@ -90,9 +90,14 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm3220g-eval/nsh2/Make.defs b/nuttx/configs/stm3220g-eval/nsh2/Make.defs index 64f158ecb..dfd41d5c5 100644 --- a/nuttx/configs/stm3220g-eval/nsh2/Make.defs +++ b/nuttx/configs/stm3220g-eval/nsh2/Make.defs @@ -90,9 +90,14 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm3220g-eval/nxwm/Make.defs b/nuttx/configs/stm3220g-eval/nxwm/Make.defs index 37280e0c4..65442d731 100644 --- a/nuttx/configs/stm3220g-eval/nxwm/Make.defs +++ b/nuttx/configs/stm3220g-eval/nxwm/Make.defs @@ -90,9 +90,14 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm3220g-eval/ostest/Make.defs b/nuttx/configs/stm3220g-eval/ostest/Make.defs index 41e8fff14..270d53339 100644 --- a/nuttx/configs/stm3220g-eval/ostest/Make.defs +++ b/nuttx/configs/stm3220g-eval/ostest/Make.defs @@ -90,9 +90,14 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm3220g-eval/telnetd/Make.defs b/nuttx/configs/stm3220g-eval/telnetd/Make.defs index 416bfaa47..0d7f1a078 100644 --- a/nuttx/configs/stm3220g-eval/telnetd/Make.defs +++ b/nuttx/configs/stm3220g-eval/telnetd/Make.defs @@ -90,9 +90,14 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm3240g-eval/dhcpd/Make.defs b/nuttx/configs/stm3240g-eval/dhcpd/Make.defs index 1c7a7cff0..e84648b10 100644 --- a/nuttx/configs/stm3240g-eval/dhcpd/Make.defs +++ b/nuttx/configs/stm3240g-eval/dhcpd/Make.defs @@ -90,9 +90,14 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm3240g-eval/discover/Make.defs b/nuttx/configs/stm3240g-eval/discover/Make.defs index 9cf9d5958..561bed1e0 100644 --- a/nuttx/configs/stm3240g-eval/discover/Make.defs +++ b/nuttx/configs/stm3240g-eval/discover/Make.defs @@ -90,9 +90,14 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm3240g-eval/nettest/Make.defs b/nuttx/configs/stm3240g-eval/nettest/Make.defs index e8af4cbb5..71764aa24 100644 --- a/nuttx/configs/stm3240g-eval/nettest/Make.defs +++ b/nuttx/configs/stm3240g-eval/nettest/Make.defs @@ -90,9 +90,14 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm3240g-eval/nsh/Make.defs b/nuttx/configs/stm3240g-eval/nsh/Make.defs index e88f1054b..71da0724a 100644 --- a/nuttx/configs/stm3240g-eval/nsh/Make.defs +++ b/nuttx/configs/stm3240g-eval/nsh/Make.defs @@ -90,9 +90,14 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm3240g-eval/nsh2/Make.defs b/nuttx/configs/stm3240g-eval/nsh2/Make.defs index 3e7fa8bd2..51aaf553e 100644 --- a/nuttx/configs/stm3240g-eval/nsh2/Make.defs +++ b/nuttx/configs/stm3240g-eval/nsh2/Make.defs @@ -90,9 +90,14 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm3240g-eval/nxconsole/Make.defs b/nuttx/configs/stm3240g-eval/nxconsole/Make.defs index aedfacc80..34865b5c2 100644 --- a/nuttx/configs/stm3240g-eval/nxconsole/Make.defs +++ b/nuttx/configs/stm3240g-eval/nxconsole/Make.defs @@ -90,9 +90,14 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm3240g-eval/nxwm/Make.defs b/nuttx/configs/stm3240g-eval/nxwm/Make.defs index 631cfab86..b15333c96 100644 --- a/nuttx/configs/stm3240g-eval/nxwm/Make.defs +++ b/nuttx/configs/stm3240g-eval/nxwm/Make.defs @@ -90,9 +90,14 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm3240g-eval/ostest/Make.defs b/nuttx/configs/stm3240g-eval/ostest/Make.defs index 875d39f22..768a095f8 100644 --- a/nuttx/configs/stm3240g-eval/ostest/Make.defs +++ b/nuttx/configs/stm3240g-eval/ostest/Make.defs @@ -90,9 +90,14 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm3240g-eval/telnetd/Make.defs b/nuttx/configs/stm3240g-eval/telnetd/Make.defs index d0ed37f28..8255e0767 100644 --- a/nuttx/configs/stm3240g-eval/telnetd/Make.defs +++ b/nuttx/configs/stm3240g-eval/telnetd/Make.defs @@ -90,9 +90,14 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm3240g-eval/webserver/Make.defs b/nuttx/configs/stm3240g-eval/webserver/Make.defs index fbe1ffb0e..855ca4186 100644 --- a/nuttx/configs/stm3240g-eval/webserver/Make.defs +++ b/nuttx/configs/stm3240g-eval/webserver/Make.defs @@ -89,9 +89,14 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm3240g-eval/xmlrpc/Make.defs b/nuttx/configs/stm3240g-eval/xmlrpc/Make.defs index 61b0d5c4e..dab94db50 100644 --- a/nuttx/configs/stm3240g-eval/xmlrpc/Make.defs +++ b/nuttx/configs/stm3240g-eval/xmlrpc/Make.defs @@ -90,9 +90,14 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm32f4discovery/nsh/Make.defs b/nuttx/configs/stm32f4discovery/nsh/Make.defs index f4110cce3..bab095abc 100644 --- a/nuttx/configs/stm32f4discovery/nsh/Make.defs +++ b/nuttx/configs/stm32f4discovery/nsh/Make.defs @@ -90,9 +90,14 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm32f4discovery/nxlines/Make.defs b/nuttx/configs/stm32f4discovery/nxlines/Make.defs index 8dab2009c..042da6a92 100644 --- a/nuttx/configs/stm32f4discovery/nxlines/Make.defs +++ b/nuttx/configs/stm32f4discovery/nxlines/Make.defs @@ -90,9 +90,14 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm32f4discovery/ostest/Make.defs b/nuttx/configs/stm32f4discovery/ostest/Make.defs index f20fddb84..10025ad9d 100644 --- a/nuttx/configs/stm32f4discovery/ostest/Make.defs +++ b/nuttx/configs/stm32f4discovery/ostest/Make.defs @@ -90,9 +90,14 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm32f4discovery/pm/Make.defs b/nuttx/configs/stm32f4discovery/pm/Make.defs index f96f439ee..1a67f1b8c 100644 --- a/nuttx/configs/stm32f4discovery/pm/Make.defs +++ b/nuttx/configs/stm32f4discovery/pm/Make.defs @@ -90,9 +90,14 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/twr-k60n512/nsh/Make.defs b/nuttx/configs/twr-k60n512/nsh/Make.defs index 99041bcc2..7bb9f09d4 100644 --- a/nuttx/configs/twr-k60n512/nsh/Make.defs +++ b/nuttx/configs/twr-k60n512/nsh/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_KINETIS_DEVKITARM),y) endif ifeq ($(CONFIG_KINETIS_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft -mlong-calls + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/twr-k60n512/ostest/Make.defs b/nuttx/configs/twr-k60n512/ostest/Make.defs index 93c887a2d..9254223dc 100644 --- a/nuttx/configs/twr-k60n512/ostest/Make.defs +++ b/nuttx/configs/twr-k60n512/ostest/Make.defs @@ -58,8 +58,12 @@ ifeq ($(CONFIG_KINETIS_DEVKITARM),y) endif ifeq ($(CONFIG_KINETIS_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft -mlong-calls + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/vsn/nsh/Make.defs b/nuttx/configs/vsn/nsh/Make.defs index abcdf49c1..292abcc72 100644 --- a/nuttx/configs/vsn/nsh/Make.defs +++ b/nuttx/configs/vsn/nsh/Make.defs @@ -70,8 +70,12 @@ ifeq ($(CONFIG_STM32_RAISONANCE),y) endif ifeq ($(CONFIG_STM32_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin - CROSSDEV = arm-nuttx-elf- - ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # OABI + # CROSSDEV = arm-nuttx-elf- + # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + # EABI + CROSSDEV = arm-nuttx-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif -- cgit v1.2.3 From e8a8129808aa7296f4c176231327d136d5fcb8c0 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 6 Oct 2012 20:10:31 +0000 Subject: Fix a recurring, cloned typo git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5220 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/configs/amber/hello/setenv.sh | 4 ++-- nuttx/configs/ea3131/nsh/setenv.sh | 4 ++-- nuttx/configs/ea3131/ostest/setenv.sh | 4 ++-- nuttx/configs/ea3131/pgnsh/setenv.sh | 4 ++-- nuttx/configs/ea3131/usbserial/setenv.sh | 4 ++-- nuttx/configs/ea3131/usbstorage/setenv.sh | 4 ++-- nuttx/configs/ea3152/ostest/setenv.sh | 4 ++-- nuttx/configs/fire-stm32v2/nsh/setenv.sh | 6 +++--- nuttx/configs/hymini-stm32v/nsh2/setenv.sh | 6 +++--- nuttx/configs/hymini-stm32v/nx/setenv.sh | 4 ++-- nuttx/configs/kwikstik-k40/ostest/setenv.sh | 4 ++-- nuttx/configs/lpc4330-xplorer/nsh/setenv.sh | 4 ++-- nuttx/configs/lpc4330-xplorer/ostest/setenv.sh | 4 ++-- nuttx/configs/lpcxpresso-lpc1768/dhcpd/setenv.sh | 2 +- nuttx/configs/lpcxpresso-lpc1768/nsh/setenv.sh | 2 +- nuttx/configs/lpcxpresso-lpc1768/nx/setenv.sh | 2 +- nuttx/configs/lpcxpresso-lpc1768/ostest/setenv.sh | 2 +- nuttx/configs/lpcxpresso-lpc1768/thttpd/setenv.sh | 2 +- nuttx/configs/lpcxpresso-lpc1768/usbstorage/setenv.sh | 2 +- nuttx/configs/mcu123-lpc214x/composite/setenv.sh | 4 ++-- nuttx/configs/micropendous3/hello/setenv.sh | 4 ++-- nuttx/configs/mirtoo/nsh/setenv.sh | 4 ++-- nuttx/configs/mirtoo/nxffs/setenv.sh | 4 ++-- nuttx/configs/mirtoo/ostest/setenv.sh | 4 ++-- nuttx/configs/olimex-stm32-p107/nsh/setenv.sh | 6 +++--- nuttx/configs/olimex-stm32-p107/ostest/setenv.sh | 6 +++--- nuttx/configs/pcblogic-pic32mx/nsh/setenv.sh | 2 +- nuttx/configs/pcblogic-pic32mx/ostest/setenv.sh | 2 +- nuttx/configs/pic32-starterkit/nsh/setenv.sh | 2 +- nuttx/configs/pic32-starterkit/nsh2/setenv.sh | 2 +- nuttx/configs/pic32-starterkit/ostest/setenv.sh | 2 +- nuttx/configs/pic32mx7mmb/nsh/setenv.sh | 2 +- nuttx/configs/pic32mx7mmb/ostest/setenv.sh | 2 +- nuttx/configs/shenzhou/nsh/setenv.sh | 6 +++--- nuttx/configs/shenzhou/nxwm/setenv.sh | 6 +++--- nuttx/configs/stm3210e-eval/composite/setenv.sh | 6 +++--- nuttx/configs/stm3210e-eval/nsh2/setenv.sh | 6 +++--- nuttx/configs/stm3210e-eval/nx/setenv.sh | 4 ++-- nuttx/configs/stm3210e-eval/nxconsole/setenv.sh | 4 ++-- nuttx/configs/stm3210e-eval/nxtext/setenv.sh | 4 ++-- nuttx/configs/stm3210e-eval/pm/setenv.sh | 6 +++--- nuttx/configs/stm3220g-eval/dhcpd/setenv.sh | 6 +++--- nuttx/configs/stm3220g-eval/nettest/setenv.sh | 6 +++--- nuttx/configs/stm3220g-eval/nsh/setenv.sh | 6 +++--- nuttx/configs/stm3220g-eval/nsh2/setenv.sh | 6 +++--- nuttx/configs/stm3220g-eval/nxwm/setenv.sh | 6 +++--- nuttx/configs/stm3220g-eval/ostest/setenv.sh | 6 +++--- nuttx/configs/stm3220g-eval/telnetd/setenv.sh | 6 +++--- nuttx/configs/stm3240g-eval/dhcpd/setenv.sh | 6 +++--- nuttx/configs/stm3240g-eval/discover/setenv.sh | 6 +++--- nuttx/configs/stm3240g-eval/nettest/setenv.sh | 6 +++--- nuttx/configs/stm3240g-eval/nsh/setenv.sh | 6 +++--- nuttx/configs/stm3240g-eval/nsh2/setenv.sh | 6 +++--- nuttx/configs/stm3240g-eval/nxconsole/setenv.sh | 6 +++--- nuttx/configs/stm3240g-eval/nxwm/setenv.sh | 6 +++--- nuttx/configs/stm3240g-eval/ostest/setenv.sh | 6 +++--- nuttx/configs/stm3240g-eval/telnetd/setenv.sh | 6 +++--- nuttx/configs/stm3240g-eval/webserver/setenv.sh | 6 +++--- nuttx/configs/stm3240g-eval/xmlrpc/setenv.sh | 6 +++--- nuttx/configs/stm32f4discovery/nsh/setenv.sh | 6 +++--- nuttx/configs/stm32f4discovery/nxlines/setenv.sh | 6 +++--- nuttx/configs/stm32f4discovery/ostest/setenv.sh | 6 +++--- nuttx/configs/stm32f4discovery/pm/setenv.sh | 6 +++--- nuttx/configs/sure-pic32mx/nsh/setenv.sh | 2 +- nuttx/configs/sure-pic32mx/ostest/setenv.sh | 2 +- nuttx/configs/sure-pic32mx/usbnsh/setenv.sh | 2 +- nuttx/configs/teensy/hello/setenv.sh | 4 ++-- nuttx/configs/teensy/nsh/setenv.sh | 4 ++-- nuttx/configs/teensy/usbstorage/setenv.sh | 4 ++-- nuttx/configs/twr-k60n512/nsh/setenv.sh | 4 ++-- nuttx/configs/twr-k60n512/ostest/setenv.sh | 4 ++-- nuttx/configs/ubw32/nsh/setenv.sh | 2 +- nuttx/configs/ubw32/ostest/setenv.sh | 2 +- 73 files changed, 159 insertions(+), 159 deletions(-) (limited to 'nuttx') diff --git a/nuttx/configs/amber/hello/setenv.sh b/nuttx/configs/amber/hello/setenv.sh index 094bad8b9..9b350a2c4 100755 --- a/nuttx/configs/amber/hello/setenv.sh +++ b/nuttx/configs/amber/hello/setenv.sh @@ -47,13 +47,13 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the WinAVR +# This is the Cygwin path to the location where I installed the WinAVR # toolchain under windows. This is *not* the default install # location so you will probably have to edit this. You will also have # to edit this if you install the Linux AVR toolchain as well #export TOOLCHAIN_BIN="/cygdrive/c/WinAVR/bin" -# This the Cygwin path to the location where I build the buildroot +# This is the Cygwin path to the location where I build the buildroot # toolchain. export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_avr/staging_dir/bin" diff --git a/nuttx/configs/ea3131/nsh/setenv.sh b/nuttx/configs/ea3131/nsh/setenv.sh index 00b1e0c43..7907d24e9 100755 --- a/nuttx/configs/ea3131/nsh/setenv.sh +++ b/nuttx/configs/ea3131/nsh/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/ea3131/ostest/setenv.sh b/nuttx/configs/ea3131/ostest/setenv.sh index cd894a300..2c3453d07 100755 --- a/nuttx/configs/ea3131/ostest/setenv.sh +++ b/nuttx/configs/ea3131/ostest/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/ea3131/pgnsh/setenv.sh b/nuttx/configs/ea3131/pgnsh/setenv.sh index ead7c9ffa..adec8bc78 100755 --- a/nuttx/configs/ea3131/pgnsh/setenv.sh +++ b/nuttx/configs/ea3131/pgnsh/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/ea3131/usbserial/setenv.sh b/nuttx/configs/ea3131/usbserial/setenv.sh index 69a6bb442..51d3d5250 100755 --- a/nuttx/configs/ea3131/usbserial/setenv.sh +++ b/nuttx/configs/ea3131/usbserial/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/ea3131/usbstorage/setenv.sh b/nuttx/configs/ea3131/usbstorage/setenv.sh index 648150228..bf0fb65a4 100755 --- a/nuttx/configs/ea3131/usbstorage/setenv.sh +++ b/nuttx/configs/ea3131/usbstorage/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/ea3152/ostest/setenv.sh b/nuttx/configs/ea3152/ostest/setenv.sh index 418f4701e..d65858918 100755 --- a/nuttx/configs/ea3152/ostest/setenv.sh +++ b/nuttx/configs/ea3152/ostest/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/fire-stm32v2/nsh/setenv.sh b/nuttx/configs/fire-stm32v2/nsh/setenv.sh index e6f4ee2e0..25afca04c 100755 --- a/nuttx/configs/fire-stm32v2/nsh/setenv.sh +++ b/nuttx/configs/fire-stm32v2/nsh/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the RIDE +# This is the Cygwin path to the location where I installed the RIDE # toolchain under windows. You will also have to edit this if you install # the RIDE toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" @@ -65,7 +65,7 @@ export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/hymini-stm32v/nsh2/setenv.sh b/nuttx/configs/hymini-stm32v/nsh2/setenv.sh index 37ae1800b..97d7c7993 100755 --- a/nuttx/configs/hymini-stm32v/nsh2/setenv.sh +++ b/nuttx/configs/hymini-stm32v/nsh2/setenv.sh @@ -47,17 +47,17 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the RIDE +# This is the Cygwin path to the location where I installed the RIDE # toolchain under windows. You will also have to edit this if you install # the RIDE toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/hymini-stm32v/nx/setenv.sh b/nuttx/configs/hymini-stm32v/nx/setenv.sh index 4e9fdb4ec..afaa91789 100755 --- a/nuttx/configs/hymini-stm32v/nx/setenv.sh +++ b/nuttx/configs/hymini-stm32v/nx/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/kwikstik-k40/ostest/setenv.sh b/nuttx/configs/kwikstik-k40/ostest/setenv.sh index 089419ac7..3acbddea4 100755 --- a/nuttx/configs/kwikstik-k40/ostest/setenv.sh +++ b/nuttx/configs/kwikstik-k40/ostest/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/lpc4330-xplorer/nsh/setenv.sh b/nuttx/configs/lpc4330-xplorer/nsh/setenv.sh index 64109ce38..c5ce2099b 100755 --- a/nuttx/configs/lpc4330-xplorer/nsh/setenv.sh +++ b/nuttx/configs/lpc4330-xplorer/nsh/setenv.sh @@ -55,7 +55,7 @@ export TOOLCHAIN_BIN="/cygdrive/c/code_red/RedSuite_4.2.3_379/redsuite/Tools/bin #export SCRIPT_BIN="/cygdrive/c/code_red/RedSuite_4.2.3_379/redsuite/bin" export SCRIPT_BIN="/cygdrive/c/nxp/LPCXpresso_4.2.3_292/lpcxpresso/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" @@ -70,7 +70,7 @@ export SCRIPT_BIN="/cygdrive/c/nxp/LPCXpresso_4.2.3_292/lpcxpresso/bin" #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" #export SCRIPT_BIN= -# This the Cygwin path to the location where I build the buildroot +# 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 SCRIPT_BIN= diff --git a/nuttx/configs/lpc4330-xplorer/ostest/setenv.sh b/nuttx/configs/lpc4330-xplorer/ostest/setenv.sh index 8ac6da66b..e5a5ef3d1 100755 --- a/nuttx/configs/lpc4330-xplorer/ostest/setenv.sh +++ b/nuttx/configs/lpc4330-xplorer/ostest/setenv.sh @@ -55,7 +55,7 @@ export TOOLCHAIN_BIN="/cygdrive/c/code_red/RedSuite_4.2.3_379/redsuite/Tools/bin #export SCRIPT_BIN="/cygdrive/c/code_red/RedSuite_4.2.3_379/redsuite/bin" export SCRIPT_BIN="/cygdrive/c/nxp/LPCXpresso_4.2.3_292/lpcxpresso/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" @@ -70,7 +70,7 @@ export SCRIPT_BIN="/cygdrive/c/nxp/LPCXpresso_4.2.3_292/lpcxpresso/bin" #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" #export SCRIPT_BIN= -# This the Cygwin path to the location where I build the buildroot +# 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 SCRIPT_BIN= diff --git a/nuttx/configs/lpcxpresso-lpc1768/dhcpd/setenv.sh b/nuttx/configs/lpcxpresso-lpc1768/dhcpd/setenv.sh index 6bc6e10c9..03641fd61 100755 --- a/nuttx/configs/lpcxpresso-lpc1768/dhcpd/setenv.sh +++ b/nuttx/configs/lpcxpresso-lpc1768/dhcpd/setenv.sh @@ -47,7 +47,7 @@ WD=`pwd` # This is the default install location for Code Red on Linux export TOOLCHAIN_BIN="/usr/local/LPCXpresso/tools/bin" -# This the Cygwin path to the LPCXpresso 3.6 install location under Windows +# This is the Cygwin path to the LPCXpresso 3.6 install location under Windows #export TOOLCHAIN_BIN="/cygdrive/c/nxp/lpcxpresso_3.6/Tools/bin" # This is the path to the LPCXpression tool subdirectory diff --git a/nuttx/configs/lpcxpresso-lpc1768/nsh/setenv.sh b/nuttx/configs/lpcxpresso-lpc1768/nsh/setenv.sh index 77f745c76..46d5b3261 100755 --- a/nuttx/configs/lpcxpresso-lpc1768/nsh/setenv.sh +++ b/nuttx/configs/lpcxpresso-lpc1768/nsh/setenv.sh @@ -47,7 +47,7 @@ WD=`pwd` # This is the default install location for Code Red on Linux export TOOLCHAIN_BIN="/usr/local/LPCXpresso/tools/bin" -# This the Cygwin path to the LPCXpresso 3.6 install location under Windows +# This is the Cygwin path to the LPCXpresso 3.6 install location under Windows #export TOOLCHAIN_BIN="/cygdrive/c/nxp/lpcxpresso_3.6/Tools/bin" # This is the path to the LPCXpression tool subdirectory diff --git a/nuttx/configs/lpcxpresso-lpc1768/nx/setenv.sh b/nuttx/configs/lpcxpresso-lpc1768/nx/setenv.sh index 711d92ea4..2f04a8ac6 100755 --- a/nuttx/configs/lpcxpresso-lpc1768/nx/setenv.sh +++ b/nuttx/configs/lpcxpresso-lpc1768/nx/setenv.sh @@ -47,7 +47,7 @@ WD=`pwd` # This is the default install location for Code Red on Linux export TOOLCHAIN_BIN="/usr/local/LPCXpresso/tools/bin" -# This the Cygwin path to the LPCXpresso 3.6 install location under Windows +# This is the Cygwin path to the LPCXpresso 3.6 install location under Windows #export TOOLCHAIN_BIN="/cygdrive/c/nxp/lpcxpresso_3.6/Tools/bin" # This is the path to the LPCXpression tool subdirectory diff --git a/nuttx/configs/lpcxpresso-lpc1768/ostest/setenv.sh b/nuttx/configs/lpcxpresso-lpc1768/ostest/setenv.sh index db976c946..724d1420d 100755 --- a/nuttx/configs/lpcxpresso-lpc1768/ostest/setenv.sh +++ b/nuttx/configs/lpcxpresso-lpc1768/ostest/setenv.sh @@ -47,7 +47,7 @@ WD=`pwd` # This is the default install location for Code Red on Linux export TOOLCHAIN_BIN="/usr/local/LPCXpresso/tools/bin" -# This the Cygwin path to the LPCXpresso 3.6 install location under Windows +# This is the Cygwin path to the LPCXpresso 3.6 install location under Windows #export TOOLCHAIN_BIN="/cygdrive/c/nxp/lpcxpresso_3.6/Tools/bin" # This is the path to the LPCXpression tool subdirectory diff --git a/nuttx/configs/lpcxpresso-lpc1768/thttpd/setenv.sh b/nuttx/configs/lpcxpresso-lpc1768/thttpd/setenv.sh index 158c8a442..7156a371d 100755 --- a/nuttx/configs/lpcxpresso-lpc1768/thttpd/setenv.sh +++ b/nuttx/configs/lpcxpresso-lpc1768/thttpd/setenv.sh @@ -49,7 +49,7 @@ export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" # This is the default install location for Code Red on Linux export TOOLCHAIN_BIN="/usr/local/LPCXpresso/tools/bin" -# This the Cygwin path to the LPCXpresso 3.6 install location under Windows +# This is the Cygwin path to the LPCXpresso 3.6 install location under Windows #export TOOLCHAIN_BIN="/cygdrive/c/nxp/lpcxpresso_3.6/Tools/bin" # This is the path to the LPCXpression tool subdirectory diff --git a/nuttx/configs/lpcxpresso-lpc1768/usbstorage/setenv.sh b/nuttx/configs/lpcxpresso-lpc1768/usbstorage/setenv.sh index 036de7aef..8c4039ddd 100755 --- a/nuttx/configs/lpcxpresso-lpc1768/usbstorage/setenv.sh +++ b/nuttx/configs/lpcxpresso-lpc1768/usbstorage/setenv.sh @@ -47,7 +47,7 @@ WD=`pwd` # This is the default install location for Code Red on Linux export TOOLCHAIN_BIN="/usr/local/LPCXpresso/tools/bin" -# This the Cygwin path to the LPCXpresso 3.6 install location under Windows +# This is the Cygwin path to the LPCXpresso 3.6 install location under Windows #export TOOLCHAIN_BIN="/cygdrive/c/nxp/lpcxpresso_3.6/Tools/bin" # This is the path to the LPCXpression tool subdirectory diff --git a/nuttx/configs/mcu123-lpc214x/composite/setenv.sh b/nuttx/configs/mcu123-lpc214x/composite/setenv.sh index f2fb6cb4c..a81cb395b 100755 --- a/nuttx/configs/mcu123-lpc214x/composite/setenv.sh +++ b/nuttx/configs/mcu123-lpc214x/composite/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/micropendous3/hello/setenv.sh b/nuttx/configs/micropendous3/hello/setenv.sh index 8e8830dc7..076ab237e 100755 --- a/nuttx/configs/micropendous3/hello/setenv.sh +++ b/nuttx/configs/micropendous3/hello/setenv.sh @@ -47,13 +47,13 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the WinAVR +# This is the Cygwin path to the location where I installed the WinAVR # toolchain under windows. This is *not* the default install # location so you will probably have to edit this. You will also have # to edit this if you install the Linux AVR toolchain as well #export TOOLCHAIN_BIN="/cygdrive/c/WinAVR/bin" -# This the Cygwin path to the location where I build the buildroot +# This is the Cygwin path to the location where I build the buildroot # toolchain. export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_avr/staging_dir/bin" diff --git a/nuttx/configs/mirtoo/nsh/setenv.sh b/nuttx/configs/mirtoo/nsh/setenv.sh index 95a5e8d30..e19bcb407 100755 --- a/nuttx/configs/mirtoo/nsh/setenv.sh +++ b/nuttx/configs/mirtoo/nsh/setenv.sh @@ -45,7 +45,7 @@ if [ ! -x "setenv.sh" ]; then exit 1 fi -# This the Cygwin path to the location where I installed the MicroChip +# This is the Cygwin path to the location where I installed the MicroChip # PIC32MX C32 toolchain under windows. This is *not* the default install # location so you will probably have to edit this. You will also have # to edit this if you install a different version of if you install the @@ -58,7 +58,7 @@ export TOOLCHAIN_BIN="/cygdrive/c/MicroChip/mplabc32/v1.12/bin" # version of if you install the toolchain at a different location #export TOOLCHAIN_BIN="/opt/microchip/xc32/v1.00/bin" -# This the Cygwin path to the location where I installed the Pinguino +# This is the Cygwin path to the location where I installed the Pinguino # toolchain under Windows. You will have to edit this if you install the # tool chain in a different location or use a different version. /bin # needs to precede the tool path or otherwise you will get diff --git a/nuttx/configs/mirtoo/nxffs/setenv.sh b/nuttx/configs/mirtoo/nxffs/setenv.sh index 34f8d3ef1..1a6279ef1 100755 --- a/nuttx/configs/mirtoo/nxffs/setenv.sh +++ b/nuttx/configs/mirtoo/nxffs/setenv.sh @@ -45,7 +45,7 @@ if [ ! -x "setenv.sh" ]; then exit 1 fi -# This the Cygwin path to the location where I installed the MicroChip +# This is the Cygwin path to the location where I installed the MicroChip # PIC32MX C32 toolchain under windows. This is *not* the default install # location so you will probably have to edit this. You will also have # to edit this if you install a different version of if you install the @@ -58,7 +58,7 @@ export TOOLCHAIN_BIN="/cygdrive/c/MicroChip/mplabc32/v1.12/bin" # version of if you install the toolchain at a different location #export TOOLCHAIN_BIN="/opt/microchip/xc32/v1.00/bin" -# This the Cygwin path to the location where I installed the Pinguino +# This is the Cygwin path to the location where I installed the Pinguino # toolchain under Windows. You will have to edit this if you install the # tool chain in a different location or use a different version. /bin # needs to precede the tool path or otherwise you will get diff --git a/nuttx/configs/mirtoo/ostest/setenv.sh b/nuttx/configs/mirtoo/ostest/setenv.sh index 28177a539..dcdd5d978 100755 --- a/nuttx/configs/mirtoo/ostest/setenv.sh +++ b/nuttx/configs/mirtoo/ostest/setenv.sh @@ -45,7 +45,7 @@ if [ ! -x "setenv.sh" ]; then exit 1 fi -# This the Cygwin path to the location where I installed the MicroChip +# This is the Cygwin path to the location where I installed the MicroChip # PIC32MX C32 toolchain under windows. This is *not* the default install # location so you will probably have to edit this. You will also have # to edit this if you install a different version of if you install the @@ -58,7 +58,7 @@ export TOOLCHAIN_BIN="/cygdrive/c/MicroChip/mplabc32/v1.12/bin" # version of if you install the toolchain at a different location #export TOOLCHAIN_BIN="/opt/microchip/xc32/v1.00/bin" -# This the Cygwin path to the location where I installed the Pinguino +# This is the Cygwin path to the location where I installed the Pinguino # toolchain under Windows. You will have to edit this if you install the # tool chain in a different location or use a different version. /bin # needs to precede the tool path or otherwise you will get diff --git a/nuttx/configs/olimex-stm32-p107/nsh/setenv.sh b/nuttx/configs/olimex-stm32-p107/nsh/setenv.sh index 004f025b8..1f634770a 100755 --- a/nuttx/configs/olimex-stm32-p107/nsh/setenv.sh +++ b/nuttx/configs/olimex-stm32-p107/nsh/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the RIDE +# This is the Cygwin path to the location where I installed the RIDE # toolchain under windows. You will also have to edit this if you install # the RIDE toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" @@ -65,7 +65,7 @@ export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/olimex-stm32-p107/ostest/setenv.sh b/nuttx/configs/olimex-stm32-p107/ostest/setenv.sh index fe40c0bc1..c09c1ee6a 100755 --- a/nuttx/configs/olimex-stm32-p107/ostest/setenv.sh +++ b/nuttx/configs/olimex-stm32-p107/ostest/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the RIDE +# This is the Cygwin path to the location where I installed the RIDE # toolchain under windows. You will also have to edit this if you install # the RIDE toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" @@ -65,7 +65,7 @@ export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/pcblogic-pic32mx/nsh/setenv.sh b/nuttx/configs/pcblogic-pic32mx/nsh/setenv.sh index 5f8bc609b..91f0b8f2c 100755 --- a/nuttx/configs/pcblogic-pic32mx/nsh/setenv.sh +++ b/nuttx/configs/pcblogic-pic32mx/nsh/setenv.sh @@ -45,7 +45,7 @@ if [ ! -x "setenv.sh" ]; then exit 1 fi -# This the Cygwin path to the location where I installed the MicroChip +# This is the Cygwin path to the location where I installed the MicroChip # PIC32MX toolchain under windows. This is *not* the default install # location so you will probably have to edit this. You will also have # to edit this if you install a different version of if you install diff --git a/nuttx/configs/pcblogic-pic32mx/ostest/setenv.sh b/nuttx/configs/pcblogic-pic32mx/ostest/setenv.sh index 1624cf8de..b10ee2157 100755 --- a/nuttx/configs/pcblogic-pic32mx/ostest/setenv.sh +++ b/nuttx/configs/pcblogic-pic32mx/ostest/setenv.sh @@ -45,7 +45,7 @@ if [ ! -x "setenv.sh" ]; then exit 1 fi -# This the Cygwin path to the location where I installed the MicroChip +# This is the Cygwin path to the location where I installed the MicroChip # PIC32MX toolchain under windows. This is *not* the default install # location so you will probably have to edit this. You will also have # to edit this if you install a different version of if you install diff --git a/nuttx/configs/pic32-starterkit/nsh/setenv.sh b/nuttx/configs/pic32-starterkit/nsh/setenv.sh index 540ade226..bd024bca0 100755 --- a/nuttx/configs/pic32-starterkit/nsh/setenv.sh +++ b/nuttx/configs/pic32-starterkit/nsh/setenv.sh @@ -45,7 +45,7 @@ if [ ! -x "setenv.sh" ]; then exit 1 fi -# This the Cygwin path to the location where I installed the MicroChip +# This is the Cygwin path to the location where I installed the MicroChip # PIC32MX toolchain under windows. This is *not* the default install # location so you will probably have to edit this. You will also have # to edit this if you install a different version of if you install diff --git a/nuttx/configs/pic32-starterkit/nsh2/setenv.sh b/nuttx/configs/pic32-starterkit/nsh2/setenv.sh index 47effba5b..cd6d8fa45 100755 --- a/nuttx/configs/pic32-starterkit/nsh2/setenv.sh +++ b/nuttx/configs/pic32-starterkit/nsh2/setenv.sh @@ -45,7 +45,7 @@ if [ ! -x "setenv.sh" ]; then exit 1 fi -# This the Cygwin path to the location where I installed the MicroChip +# This is the Cygwin path to the location where I installed the MicroChip # PIC32MX toolchain under windows. This is *not* the default install # location so you will probably have to edit this. You will also have # to edit this if you install a different version of if you install diff --git a/nuttx/configs/pic32-starterkit/ostest/setenv.sh b/nuttx/configs/pic32-starterkit/ostest/setenv.sh index 4e4777ce6..08dac3a15 100755 --- a/nuttx/configs/pic32-starterkit/ostest/setenv.sh +++ b/nuttx/configs/pic32-starterkit/ostest/setenv.sh @@ -45,7 +45,7 @@ if [ ! -x "setenv.sh" ]; then exit 1 fi -# This the Cygwin path to the location where I installed the MicroChip +# This is the Cygwin path to the location where I installed the MicroChip # PIC32MX toolchain under windows. This is *not* the default install # location so you will probably have to edit this. You will also have # to edit this if you install a different version of if you install diff --git a/nuttx/configs/pic32mx7mmb/nsh/setenv.sh b/nuttx/configs/pic32mx7mmb/nsh/setenv.sh index aefb891cf..82518d740 100755 --- a/nuttx/configs/pic32mx7mmb/nsh/setenv.sh +++ b/nuttx/configs/pic32mx7mmb/nsh/setenv.sh @@ -45,7 +45,7 @@ if [ ! -x "setenv.sh" ]; then exit 1 fi -# This the Cygwin path to the location where I installed the MicroChip +# This is the Cygwin path to the location where I installed the MicroChip # PIC32MX toolchain under windows. This is *not* the default install # location so you will probably have to edit this. You will also have # to edit this if you install a different version of if you install diff --git a/nuttx/configs/pic32mx7mmb/ostest/setenv.sh b/nuttx/configs/pic32mx7mmb/ostest/setenv.sh index a960d4b7c..b7cf576fb 100755 --- a/nuttx/configs/pic32mx7mmb/ostest/setenv.sh +++ b/nuttx/configs/pic32mx7mmb/ostest/setenv.sh @@ -45,7 +45,7 @@ if [ ! -x "setenv.sh" ]; then exit 1 fi -# This the Cygwin path to the location where I installed the MicroChip +# This is the Cygwin path to the location where I installed the MicroChip # PIC32MX toolchain under windows. This is *not* the default install # location so you will probably have to edit this. You will also have # to edit this if you install a different version of if you install diff --git a/nuttx/configs/shenzhou/nsh/setenv.sh b/nuttx/configs/shenzhou/nsh/setenv.sh index d57d6f003..96fe2dd34 100755 --- a/nuttx/configs/shenzhou/nsh/setenv.sh +++ b/nuttx/configs/shenzhou/nsh/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the RIDE +# This is the Cygwin path to the location where I installed the RIDE # toolchain under windows. You will also have to edit this if you install # the RIDE toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" @@ -65,7 +65,7 @@ export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/shenzhou/nxwm/setenv.sh b/nuttx/configs/shenzhou/nxwm/setenv.sh index 7f00448a6..eb2c424f4 100755 --- a/nuttx/configs/shenzhou/nxwm/setenv.sh +++ b/nuttx/configs/shenzhou/nxwm/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the RIDE +# This is the Cygwin path to the location where I installed the RIDE # toolchain under windows. You will also have to edit this if you install # the RIDE toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" @@ -65,7 +65,7 @@ export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/stm3210e-eval/composite/setenv.sh b/nuttx/configs/stm3210e-eval/composite/setenv.sh index ce267428b..620f842bd 100755 --- a/nuttx/configs/stm3210e-eval/composite/setenv.sh +++ b/nuttx/configs/stm3210e-eval/composite/setenv.sh @@ -47,17 +47,17 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the RIDE +# This is the Cygwin path to the location where I installed the RIDE # toolchain under windows. You will also have to edit this if you install # the RIDE toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/stm3210e-eval/nsh2/setenv.sh b/nuttx/configs/stm3210e-eval/nsh2/setenv.sh index 425acf89e..1fa193a57 100755 --- a/nuttx/configs/stm3210e-eval/nsh2/setenv.sh +++ b/nuttx/configs/stm3210e-eval/nsh2/setenv.sh @@ -47,17 +47,17 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the RIDE +# This is the Cygwin path to the location where I installed the RIDE # toolchain under windows. You will also have to edit this if you install # the RIDE toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/stm3210e-eval/nx/setenv.sh b/nuttx/configs/stm3210e-eval/nx/setenv.sh index bf9fad443..f02144943 100755 --- a/nuttx/configs/stm3210e-eval/nx/setenv.sh +++ b/nuttx/configs/stm3210e-eval/nx/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/stm3210e-eval/nxconsole/setenv.sh b/nuttx/configs/stm3210e-eval/nxconsole/setenv.sh index 629770245..b0d409c60 100755 --- a/nuttx/configs/stm3210e-eval/nxconsole/setenv.sh +++ b/nuttx/configs/stm3210e-eval/nxconsole/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/stm3210e-eval/nxtext/setenv.sh b/nuttx/configs/stm3210e-eval/nxtext/setenv.sh index a36540cf1..0f3d387f5 100755 --- a/nuttx/configs/stm3210e-eval/nxtext/setenv.sh +++ b/nuttx/configs/stm3210e-eval/nxtext/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/stm3210e-eval/pm/setenv.sh b/nuttx/configs/stm3210e-eval/pm/setenv.sh index 5a02de258..d73f69a2f 100755 --- a/nuttx/configs/stm3210e-eval/pm/setenv.sh +++ b/nuttx/configs/stm3210e-eval/pm/setenv.sh @@ -47,17 +47,17 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the RIDE +# This is the Cygwin path to the location where I installed the RIDE # toolchain under windows. You will also have to edit this if you install # the RIDE toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/stm3220g-eval/dhcpd/setenv.sh b/nuttx/configs/stm3220g-eval/dhcpd/setenv.sh index f23056a01..47c4e45ba 100755 --- a/nuttx/configs/stm3220g-eval/dhcpd/setenv.sh +++ b/nuttx/configs/stm3220g-eval/dhcpd/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the RIDE +# This is the Cygwin path to the location where I installed the RIDE # toolchain under windows. You will also have to edit this if you install # the RIDE toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" @@ -65,7 +65,7 @@ export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/stm3220g-eval/nettest/setenv.sh b/nuttx/configs/stm3220g-eval/nettest/setenv.sh index 67287fd74..9586cfd4c 100755 --- a/nuttx/configs/stm3220g-eval/nettest/setenv.sh +++ b/nuttx/configs/stm3220g-eval/nettest/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the RIDE +# This is the Cygwin path to the location where I installed the RIDE # toolchain under windows. You will also have to edit this if you install # the RIDE toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" @@ -65,7 +65,7 @@ export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/stm3220g-eval/nsh/setenv.sh b/nuttx/configs/stm3220g-eval/nsh/setenv.sh index 618daf011..489322177 100755 --- a/nuttx/configs/stm3220g-eval/nsh/setenv.sh +++ b/nuttx/configs/stm3220g-eval/nsh/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the RIDE +# This is the Cygwin path to the location where I installed the RIDE # toolchain under windows. You will also have to edit this if you install # the RIDE toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" @@ -65,7 +65,7 @@ fi #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" -# This the Cygwin path to the location where I build the buildroot +# This is the Cygwin path to the location where I build the buildroot # toolchain. export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" diff --git a/nuttx/configs/stm3220g-eval/nsh2/setenv.sh b/nuttx/configs/stm3220g-eval/nsh2/setenv.sh index 5b6405fae..1e2f87b40 100755 --- a/nuttx/configs/stm3220g-eval/nsh2/setenv.sh +++ b/nuttx/configs/stm3220g-eval/nsh2/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the RIDE +# This is the Cygwin path to the location where I installed the RIDE # toolchain under windows. You will also have to edit this if you install # the RIDE toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" @@ -64,7 +64,7 @@ fi #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" -# This the Cygwin path to the location where I build the buildroot +# This is the Cygwin path to the location where I build the buildroot # toolchain. export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" diff --git a/nuttx/configs/stm3220g-eval/nxwm/setenv.sh b/nuttx/configs/stm3220g-eval/nxwm/setenv.sh index 95c73a722..ff642018e 100755 --- a/nuttx/configs/stm3220g-eval/nxwm/setenv.sh +++ b/nuttx/configs/stm3220g-eval/nxwm/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the RIDE +# This is the Cygwin path to the location where I installed the RIDE # toolchain under windows. You will also have to edit this if you install # the RIDE toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" @@ -65,7 +65,7 @@ export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" -# This the Cygwin path to the location where I build the buildroot +# This is the Cygwin path to the location where I build the buildroot # toolchain. export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" diff --git a/nuttx/configs/stm3220g-eval/ostest/setenv.sh b/nuttx/configs/stm3220g-eval/ostest/setenv.sh index 2b8e7daa7..4f886e58b 100755 --- a/nuttx/configs/stm3220g-eval/ostest/setenv.sh +++ b/nuttx/configs/stm3220g-eval/ostest/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the RIDE +# This is the Cygwin path to the location where I installed the RIDE # toolchain under windows. You will also have to edit this if you install # the RIDE toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" @@ -65,7 +65,7 @@ export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/stm3220g-eval/telnetd/setenv.sh b/nuttx/configs/stm3220g-eval/telnetd/setenv.sh index 68903d175..7e0ca9edc 100755 --- a/nuttx/configs/stm3220g-eval/telnetd/setenv.sh +++ b/nuttx/configs/stm3220g-eval/telnetd/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the RIDE +# This is the Cygwin path to the location where I installed the RIDE # toolchain under windows. You will also have to edit this if you install # the RIDE toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" @@ -65,7 +65,7 @@ export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/stm3240g-eval/dhcpd/setenv.sh b/nuttx/configs/stm3240g-eval/dhcpd/setenv.sh index 9fcb08906..5d7ee987e 100755 --- a/nuttx/configs/stm3240g-eval/dhcpd/setenv.sh +++ b/nuttx/configs/stm3240g-eval/dhcpd/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the RIDE +# This is the Cygwin path to the location where I installed the RIDE # toolchain under windows. You will also have to edit this if you install # the RIDE toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" @@ -65,7 +65,7 @@ export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/stm3240g-eval/discover/setenv.sh b/nuttx/configs/stm3240g-eval/discover/setenv.sh index ce5f031b1..fb039aa25 100755 --- a/nuttx/configs/stm3240g-eval/discover/setenv.sh +++ b/nuttx/configs/stm3240g-eval/discover/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the RIDE +# This is the Cygwin path to the location where I installed the RIDE # toolchain under windows. You will also have to edit this if you install # the RIDE toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" @@ -65,7 +65,7 @@ export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/stm3240g-eval/nettest/setenv.sh b/nuttx/configs/stm3240g-eval/nettest/setenv.sh index 2d3414d27..7f3aa05b9 100755 --- a/nuttx/configs/stm3240g-eval/nettest/setenv.sh +++ b/nuttx/configs/stm3240g-eval/nettest/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the RIDE +# This is the Cygwin path to the location where I installed the RIDE # toolchain under windows. You will also have to edit this if you install # the RIDE toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" @@ -65,7 +65,7 @@ export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/stm3240g-eval/nsh/setenv.sh b/nuttx/configs/stm3240g-eval/nsh/setenv.sh index 4d92d6bbf..a0c457dc7 100755 --- a/nuttx/configs/stm3240g-eval/nsh/setenv.sh +++ b/nuttx/configs/stm3240g-eval/nsh/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the RIDE +# This is the Cygwin path to the location where I installed the RIDE # toolchain under windows. You will also have to edit this if you install # the RIDE toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" @@ -65,7 +65,7 @@ export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/stm3240g-eval/nsh2/setenv.sh b/nuttx/configs/stm3240g-eval/nsh2/setenv.sh index 944f77734..1856591aa 100755 --- a/nuttx/configs/stm3240g-eval/nsh2/setenv.sh +++ b/nuttx/configs/stm3240g-eval/nsh2/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the RIDE +# This is the Cygwin path to the location where I installed the RIDE # toolchain under windows. You will also have to edit this if you install # the RIDE toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" @@ -65,7 +65,7 @@ export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/stm3240g-eval/nxconsole/setenv.sh b/nuttx/configs/stm3240g-eval/nxconsole/setenv.sh index a42950836..39c9d257b 100755 --- a/nuttx/configs/stm3240g-eval/nxconsole/setenv.sh +++ b/nuttx/configs/stm3240g-eval/nxconsole/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the RIDE +# This is the Cygwin path to the location where I installed the RIDE # toolchain under windows. You will also have to edit this if you install # the RIDE toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" @@ -65,7 +65,7 @@ export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/stm3240g-eval/nxwm/setenv.sh b/nuttx/configs/stm3240g-eval/nxwm/setenv.sh index a8ff5bb04..a995b02bc 100755 --- a/nuttx/configs/stm3240g-eval/nxwm/setenv.sh +++ b/nuttx/configs/stm3240g-eval/nxwm/setenv.sh @@ -47,17 +47,17 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the RIDE +# This is the Cygwin path to the location where I installed the RIDE # toolchain under windows. You will also have to edit this if you install # the RIDE toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/stm3240g-eval/ostest/setenv.sh b/nuttx/configs/stm3240g-eval/ostest/setenv.sh index 29786ec2f..795996bc0 100755 --- a/nuttx/configs/stm3240g-eval/ostest/setenv.sh +++ b/nuttx/configs/stm3240g-eval/ostest/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the RIDE +# This is the Cygwin path to the location where I installed the RIDE # toolchain under windows. You will also have to edit this if you install # the RIDE toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" @@ -65,7 +65,7 @@ export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/stm3240g-eval/telnetd/setenv.sh b/nuttx/configs/stm3240g-eval/telnetd/setenv.sh index c022d1d9b..38262453d 100755 --- a/nuttx/configs/stm3240g-eval/telnetd/setenv.sh +++ b/nuttx/configs/stm3240g-eval/telnetd/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the RIDE +# This is the Cygwin path to the location where I installed the RIDE # toolchain under windows. You will also have to edit this if you install # the RIDE toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" @@ -65,7 +65,7 @@ export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/stm3240g-eval/webserver/setenv.sh b/nuttx/configs/stm3240g-eval/webserver/setenv.sh index 2347f39d8..d4fa30fdc 100644 --- a/nuttx/configs/stm3240g-eval/webserver/setenv.sh +++ b/nuttx/configs/stm3240g-eval/webserver/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the RIDE +# This is the Cygwin path to the location where I installed the RIDE # toolchain under windows. You will also have to edit this if you install # the RIDE toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" @@ -65,7 +65,7 @@ export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/stm3240g-eval/xmlrpc/setenv.sh b/nuttx/configs/stm3240g-eval/xmlrpc/setenv.sh index 847be2a89..835018d80 100644 --- a/nuttx/configs/stm3240g-eval/xmlrpc/setenv.sh +++ b/nuttx/configs/stm3240g-eval/xmlrpc/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the RIDE +# This is the Cygwin path to the location where I installed the RIDE # toolchain under windows. You will also have to edit this if you install # the RIDE toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" @@ -65,7 +65,7 @@ export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/stm32f4discovery/nsh/setenv.sh b/nuttx/configs/stm32f4discovery/nsh/setenv.sh index 65a7a3ab4..2476845b6 100755 --- a/nuttx/configs/stm32f4discovery/nsh/setenv.sh +++ b/nuttx/configs/stm32f4discovery/nsh/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the RIDE +# This is the Cygwin path to the location where I installed the RIDE # toolchain under windows. You will also have to edit this if you install # the RIDE toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" @@ -65,7 +65,7 @@ export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/stm32f4discovery/nxlines/setenv.sh b/nuttx/configs/stm32f4discovery/nxlines/setenv.sh index e188703a0..b9815c482 100755 --- a/nuttx/configs/stm32f4discovery/nxlines/setenv.sh +++ b/nuttx/configs/stm32f4discovery/nxlines/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the RIDE +# This is the Cygwin path to the location where I installed the RIDE # toolchain under windows. You will also have to edit this if you install # the RIDE toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" @@ -65,7 +65,7 @@ export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/stm32f4discovery/ostest/setenv.sh b/nuttx/configs/stm32f4discovery/ostest/setenv.sh index d67f434d0..a67fdc5a8 100755 --- a/nuttx/configs/stm32f4discovery/ostest/setenv.sh +++ b/nuttx/configs/stm32f4discovery/ostest/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the RIDE +# This is the Cygwin path to the location where I installed the RIDE # toolchain under windows. You will also have to edit this if you install # the RIDE toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" @@ -65,7 +65,7 @@ export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/stm32f4discovery/pm/setenv.sh b/nuttx/configs/stm32f4discovery/pm/setenv.sh index ca0795942..fef2997c7 100644 --- a/nuttx/configs/stm32f4discovery/pm/setenv.sh +++ b/nuttx/configs/stm32f4discovery/pm/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the RIDE +# This is the Cygwin path to the location where I installed the RIDE # toolchain under windows. You will also have to edit this if you install # the RIDE toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" @@ -65,7 +65,7 @@ export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" #export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/sure-pic32mx/nsh/setenv.sh b/nuttx/configs/sure-pic32mx/nsh/setenv.sh index 8c4df233b..bba683609 100755 --- a/nuttx/configs/sure-pic32mx/nsh/setenv.sh +++ b/nuttx/configs/sure-pic32mx/nsh/setenv.sh @@ -45,7 +45,7 @@ if [ ! -x "setenv.sh" ]; then exit 1 fi -# This the Cygwin path to the location where I installed the MicroChip +# This is the Cygwin path to the location where I installed the MicroChip # PIC32MX toolchain under windows. This is *not* the default install # location so you will probably have to edit this. You will also have # to edit this if you install a different version of if you install diff --git a/nuttx/configs/sure-pic32mx/ostest/setenv.sh b/nuttx/configs/sure-pic32mx/ostest/setenv.sh index b26ea960e..5f0234588 100755 --- a/nuttx/configs/sure-pic32mx/ostest/setenv.sh +++ b/nuttx/configs/sure-pic32mx/ostest/setenv.sh @@ -45,7 +45,7 @@ if [ ! -x "setenv.sh" ]; then exit 1 fi -# This the Cygwin path to the location where I installed the MicroChip +# This is the Cygwin path to the location where I installed the MicroChip # PIC32MX toolchain under windows. This is *not* the default install # location so you will probably have to edit this. You will also have # to edit this if you install a different version of if you install diff --git a/nuttx/configs/sure-pic32mx/usbnsh/setenv.sh b/nuttx/configs/sure-pic32mx/usbnsh/setenv.sh index 263dfc596..62074cdb3 100755 --- a/nuttx/configs/sure-pic32mx/usbnsh/setenv.sh +++ b/nuttx/configs/sure-pic32mx/usbnsh/setenv.sh @@ -45,7 +45,7 @@ if [ ! -x "setenv.sh" ]; then exit 1 fi -# This the Cygwin path to the location where I installed the MicroChip +# This is the Cygwin path to the location where I installed the MicroChip # PIC32MX toolchain under windows. This is *not* the default install # location so you will probably have to edit this. You will also have # to edit this if you install a different version of if you install diff --git a/nuttx/configs/teensy/hello/setenv.sh b/nuttx/configs/teensy/hello/setenv.sh index d0100778a..ecb266423 100755 --- a/nuttx/configs/teensy/hello/setenv.sh +++ b/nuttx/configs/teensy/hello/setenv.sh @@ -47,13 +47,13 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the WinAVR +# This is the Cygwin path to the location where I installed the WinAVR # toolchain under windows. This is *not* the default install # location so you will probably have to edit this. You will also have # to edit this if you install the Linux AVR toolchain as well #export TOOLCHAIN_BIN="/cygdrive/c/WinAVR/bin" -# This the Cygwin path to the location where I build the buildroot +# This is the Cygwin path to the location where I build the buildroot # toolchain. export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_avr/staging_dir/bin" diff --git a/nuttx/configs/teensy/nsh/setenv.sh b/nuttx/configs/teensy/nsh/setenv.sh index f0c035bba..fb61f8577 100755 --- a/nuttx/configs/teensy/nsh/setenv.sh +++ b/nuttx/configs/teensy/nsh/setenv.sh @@ -47,13 +47,13 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the WinAVR +# This is the Cygwin path to the location where I installed the WinAVR # toolchain under windows. This is *not* the default install # location so you will probably have to edit this. You will also have # to edit this if you install the Linux AVR toolchain as well #export TOOLCHAIN_BIN="/cygdrive/c/WinAVR/bin" -# This the Cygwin path to the location where I build the buildroot +# This is the Cygwin path to the location where I build the buildroot # toolchain. export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_avr/staging_dir/bin" diff --git a/nuttx/configs/teensy/usbstorage/setenv.sh b/nuttx/configs/teensy/usbstorage/setenv.sh index a455f560a..2f80197c3 100755 --- a/nuttx/configs/teensy/usbstorage/setenv.sh +++ b/nuttx/configs/teensy/usbstorage/setenv.sh @@ -47,13 +47,13 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the WinAVR +# This is the Cygwin path to the location where I installed the WinAVR # toolchain under windows. This is *not* the default install # location so you will probably have to edit this. You will also have # to edit this if you install the Linux AVR toolchain as well #export TOOLCHAIN_BIN="/cygdrive/c/WinAVR/bin" -# This the Cygwin path to the location where I build the buildroot +# This is the Cygwin path to the location where I build the buildroot # toolchain. export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_avr/staging_dir/bin" diff --git a/nuttx/configs/twr-k60n512/nsh/setenv.sh b/nuttx/configs/twr-k60n512/nsh/setenv.sh index a780a15a7..e2725b0c3 100644 --- a/nuttx/configs/twr-k60n512/nsh/setenv.sh +++ b/nuttx/configs/twr-k60n512/nsh/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/twr-k60n512/ostest/setenv.sh b/nuttx/configs/twr-k60n512/ostest/setenv.sh index 86b6099dc..c3cc691ed 100644 --- a/nuttx/configs/twr-k60n512/ostest/setenv.sh +++ b/nuttx/configs/twr-k60n512/ostest/setenv.sh @@ -47,12 +47,12 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This the Cygwin path to the location where I installed the CodeSourcery +# This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location #export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" -# This the Cygwin path to the location where I build the buildroot +# 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" diff --git a/nuttx/configs/ubw32/nsh/setenv.sh b/nuttx/configs/ubw32/nsh/setenv.sh index 26946b1bb..ca5a097a3 100755 --- a/nuttx/configs/ubw32/nsh/setenv.sh +++ b/nuttx/configs/ubw32/nsh/setenv.sh @@ -45,7 +45,7 @@ if [ ! -x "setenv.sh" ]; then exit 1 fi -# This the Cygwin path to the location where I installed the MicroChip +# This is the Cygwin path to the location where I installed the MicroChip # PIC32MX toolchain under windows. This is *not* the default install # location so you will probably have to edit this. You will also have # to edit this if you install a different version of if you install diff --git a/nuttx/configs/ubw32/ostest/setenv.sh b/nuttx/configs/ubw32/ostest/setenv.sh index 6123ce6ba..d49019641 100755 --- a/nuttx/configs/ubw32/ostest/setenv.sh +++ b/nuttx/configs/ubw32/ostest/setenv.sh @@ -45,7 +45,7 @@ if [ ! -x "setenv.sh" ]; then exit 1 fi -# This the Cygwin path to the location where I installed the MicroChip +# This is the Cygwin path to the location where I installed the MicroChip # PIC32MX toolchain under windows. This is *not* the default install # location so you will probably have to edit this. You will also have # to edit this if you install a different version of if you install -- cgit v1.2.3 From 50ecc59c27d8b5d295c8023d2641e6c7e55e51be Mon Sep 17 00:00:00 2001 From: patacongo Date: Mon, 8 Oct 2012 18:12:53 +0000 Subject: Updates for new web site git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5221 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/Documentation/NuttX.html | 24 ++++++++++++------------ nuttx/Documentation/NuttXCommercial.html | 1 + nuttx/Documentation/NuttXLinks.html | 4 ++-- nuttx/Documentation/NuttxPortingGuide.html | 2 +- nuttx/Documentation/NxWidgets.html | 14 ++++++++++---- nuttx/Documentation/index.html | 2 +- nuttx/Documentation/redirect.html | 20 ++++++++++++++++++++ 7 files changed, 47 insertions(+), 20 deletions(-) create mode 100644 nuttx/Documentation/redirect.html (limited to 'nuttx') diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html index f22ab418c..06b61a4de 100644 --- a/nuttx/Documentation/NuttX.html +++ b/nuttx/Documentation/NuttX.html @@ -1675,7 +1675,7 @@ svn checkout -r5206 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code This port uses Serial-to-Ethernet Reference Design Kit (RDK-S2E) and has similar support as for the other Stellaris family members. Configurations are available for the OS test and for the NuttShell (NSH) - (see the NSH User Guide). + (see the NSH User Guide). The NSH configuration including networking support with a Telnet NSH console. This port was contributed by Mike Smith.

                              @@ -1854,7 +1854,7 @@ svn checkout -r5206 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code A configuration to support the NuttShell is also included. NuttX version 5.4 adds support for the HX8347 LCD on the SAM3U-EK board. This LCD support includes an example using the - NX graphics system. + NX graphics system. NuttX version 6.10 adds SPI support.

                              @@ -1930,7 +1930,7 @@ svn checkout -r5206 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code That initial, 5.6, basic release included timer interrupts and a serial console and was verified using the NuttX OS test (apps/examples/ostest). Configurations available include include a verified NuttShell (NSH) configuration - (see the NSH User Guide). + (see the NSH User Guide). The NSH configuration supports the Nucleus2G's microSD slot and additional configurations are available to exercise the the USB serial and USB mass storage devices. However, due to some technical reasons, neither the SPI nor the USB device drivers are fully verified. @@ -1971,7 +1971,7 @@ svn checkout -r5206 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code

                              Verified configurations are now available for the NuttX OS test, - for the NuttShell with networking and microSD support(NSH, see the NSH User Guide), + for the NuttShell with networking and microSD support(NSH, see the NSH User Guide), for the NuttX network test, for the THTTPD webserver, for USB serial deive and USB storage devices examples, and for the USB host HID keyboard driver. Support for the USB host mass storage device can optionally be configured for the NSH example. @@ -2054,7 +2054,7 @@ svn checkout -r5206 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code STATUS: As of this writing, the basic port is complete and passes the NuttX OS test. An additional, validated configuration exists for the NuttShell (NSH, see the - NSH User Guide). + NSH User Guide). This basic TWR-K60N512 first appeared in NuttX-6.8. Ethernet and SD card (SDHC) drivers also exist: The SDHC driver is partially integrated in to the NSH configuration but has some outstanding issues; @@ -2083,7 +2083,7 @@ svn checkout -r5206 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code

                            • NuttX-6.12 The basic port is complete and first appeared in NuttX-6.12. The initial port passes the NuttX OS test and includes a validated configuration for the NuttShell (NSH, see the - NSH User Guide) as well as several other configurations. + NSH User Guide) as well as several other configurations.
                            • NuttX-6.13-6.16 Additional drivers and configurations were added in NuttX 6.13-6.16. @@ -2266,7 +2266,7 @@ svn checkout -r5206 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code a "Hello, World!!" example that demonstrates initialization of the OS, creation of a simple task, and serial console output as well as a somewhat simplified NuttShell (NSH) configuration (see the - NSH User Guide). + NSH User Guide).

                              An SPI driver and a USB device driver exist for the AT90USB as well @@ -2349,7 +2349,7 @@ svn checkout -r5206 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code The port successfully passes the NuttX OS test (apps/examples/ostest).

                            • - A NuttShell (NSH) configuration is in place (see the NSH User Guide). + A NuttShell (NSH) configuration is in place (see the NSH User Guide). Testing of that configuration has been postponed (because it got bumped by the Olimex LPC1766-STK port). Current Status: I think I have a hardware problem with my serial port setup. There is a good chance that the NSH port is complete and functional, but I am not yet able to demonstrate that. @@ -2502,7 +2502,7 @@ svn checkout -r5206 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code The NSH configuration includes support for a serial console and for the SST25 serial FLASH and the PGA117 amplifier/multiplexer on board the module. The NSH configuration is set up to use the NuttX wear-leveling FLASH file system (NXFFS). The PGA117, however, is not yet fully integrated to support ADC sampling. - See the NSH User Guide for further information about NSH. + See the NSH User Guide for further information about NSH. The first verified port to the Mirtoo module was available with the NuttX 6.20 release.

                            @@ -2524,7 +2524,7 @@ svn checkout -r5206 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code

                            STATUS: The basic port is code complete and fully verified in NuttX 6.13. - Available configurations include the OS test and the NuttShell (NSH - see the NSH User Guide). + Available configurations include the OS test and the NuttShell (NSH - see the NSH User Guide).

                          • UBW32 Board from Sparkfun This is the port to the Sparkfun UBW32 board. @@ -2535,7 +2535,7 @@ svn checkout -r5206 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code

                            STATUS: The basic port is code complete and fully verified in NuttX 6.18. - Available configurations include the OS test and the NuttShell (NSH - see the NSH User Guide). + Available configurations include the OS test and the NuttShell (NSH - see the NSH User Guide). USB has not yet been fully tested but on first pass appears to be functional.

                          @@ -2562,7 +2562,7 @@ svn checkout -r5206 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code This NuttX port is code complete and has considerable test testing. The port for this board was completed in NuttX 6.11, but still required a few bug fixes before it will be ready for prime time. The fully verified port first appeared in NuttX 6.13. - Available configurations include the OS test and the NuttShell (NSH - see the NSH User Guide). + Available configurations include the OS test and the NuttShell (NSH - see the NSH User Guide). An untested USB device-side driver is available in the source tree. A more complete port would include support of the USB OTG port and of the LCD display on this board. Those drivers are not yet available as of this writing. diff --git a/nuttx/Documentation/NuttXCommercial.html b/nuttx/Documentation/NuttXCommercial.html index a3d4766f9..9161df40d 100644 --- a/nuttx/Documentation/NuttXCommercial.html +++ b/nuttx/Documentation/NuttXCommercial.html @@ -50,6 +50,7 @@
                        • NX-Engineering
                        • Raztek Solutions
                        • +
                        • North Shore Design Group
                        • 2G Engineering
                        • ISOTEL Research
                        • DSPWorks
                        • diff --git a/nuttx/Documentation/NuttXLinks.html b/nuttx/Documentation/NuttXLinks.html index b69a354fa..647607e11 100644 --- a/nuttx/Documentation/NuttXLinks.html +++ b/nuttx/Documentation/NuttXLinks.html @@ -18,14 +18,14 @@   -
                        • Home
                        • +
                        • Home
                        • SourceForge
                        • FreshMeat
                        • Forum
                        • Ohloh
                        • OSChina
                        • Downloads
                        • -
                        • Wiki
                        • +
                        • Wiki
                        • Toolchains
                        • Browse SVN
                        • Free Ports
                        • diff --git a/nuttx/Documentation/NuttxPortingGuide.html b/nuttx/Documentation/NuttxPortingGuide.html index 21ae44144..bf2a0cc4f 100644 --- a/nuttx/Documentation/NuttxPortingGuide.html +++ b/nuttx/Documentation/NuttxPortingGuide.html @@ -4222,7 +4222,7 @@ build
                        • CONFIG_PAGING: If set =y in your configation file, this setting will enable the on-demand paging feature as described in - NuttXDemandPaging.html. + NuttXDemandPaging.html.
                        diff --git a/nuttx/Documentation/NxWidgets.html b/nuttx/Documentation/NxWidgets.html index 1678d9ebe..548ab5e0a 100644 --- a/nuttx/Documentation/NxWidgets.html +++ b/nuttx/Documentation/NxWidgets.html @@ -62,21 +62,27 @@
                        • NxWidgets-1.0: - Documentation, and + Documentation, and Downloads
                        • -
                        • +
                        • http://nuttx.org/nxwidgets_v1_0/ NxWidgets-1.1: - Documentation, + Documentation, Release notes, and Downloads
                        • NxWidgets-1.2: - Documentation, + Documentation, Release notes, and Downloads
                        • +
                        • + NxWidgets-1.3: + Documentation, + Release notes, and + Downloads +
                        • Thanks go to Jose Pablo Carballo for contributing this! diff --git a/nuttx/Documentation/index.html b/nuttx/Documentation/index.html index da4c107f0..ea2e3a327 100644 --- a/nuttx/Documentation/index.html +++ b/nuttx/Documentation/index.html @@ -12,7 +12,7 @@

                          This page uses frames, but your browser doesn't support them. - Try this link. + Try this link.

                          diff --git a/nuttx/Documentation/redirect.html b/nuttx/Documentation/redirect.html new file mode 100644 index 000000000..13e75cd05 --- /dev/null +++ b/nuttx/Documentation/redirect.html @@ -0,0 +1,20 @@ + + + +The NuttX RTOS + + + + + + +
                          +

                          The NuttX RTOS

                          +
                          +

                          +
                          + The NuttX RTOS web site has moved to nuttx.org. + Please update your bookmarks and wait while you are redirected there. +
                          + + -- cgit v1.2.3 From 3d754095f92510813006fe42564e5eb473604e1f Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 10 Oct 2012 12:56:02 +0000 Subject: Change the default path to the buildroot bin/ directory in all setenv.sh files git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5222 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/configs/c5471evm/httpd/setenv.sh | 2 +- nuttx/configs/c5471evm/nettest/setenv.sh | 2 +- nuttx/configs/c5471evm/nsh/setenv.sh | 2 +- nuttx/configs/c5471evm/ostest/setenv.sh | 2 +- nuttx/configs/compal_e88/nsh_highram/setenv.sh | 2 +- nuttx/configs/compal_e99/nsh_compalram/setenv.sh | 2 +- nuttx/configs/compal_e99/nsh_highram/setenv.sh | 2 +- nuttx/configs/demo9s12ne64/ostest/setenv.sh | 2 +- nuttx/configs/eagle100/httpd/setenv.sh | 2 +- nuttx/configs/eagle100/nettest/setenv.sh | 2 +- nuttx/configs/eagle100/nsh/setenv.sh | 2 +- nuttx/configs/eagle100/nxflat/setenv.sh | 2 +- nuttx/configs/eagle100/ostest/setenv.sh | 2 +- nuttx/configs/eagle100/thttpd/setenv.sh | 2 +- nuttx/configs/ekk-lm3s9b96/nsh/setenv.sh | 2 +- nuttx/configs/ekk-lm3s9b96/ostest/setenv.sh | 2 +- nuttx/configs/hymini-stm32v/buttons/setenv.sh | 2 +- nuttx/configs/hymini-stm32v/nsh/setenv.sh | 2 +- nuttx/configs/hymini-stm32v/nxlines/setenv.sh | 2 +- nuttx/configs/hymini-stm32v/usbserial/setenv.sh | 2 +- nuttx/configs/hymini-stm32v/usbstorage/setenv.sh | 2 +- nuttx/configs/lincoln60/nsh/setenv.sh | 2 +- nuttx/configs/lincoln60/ostest/setenv.sh | 2 +- nuttx/configs/lm3s6432-s2e/nsh/setenv.sh | 2 +- nuttx/configs/lm3s6432-s2e/ostest/setenv.sh | 2 +- nuttx/configs/lm3s6965-ek/nsh/setenv.sh | 2 +- nuttx/configs/lm3s6965-ek/nx/setenv.sh | 2 +- nuttx/configs/lm3s6965-ek/ostest/setenv.sh | 2 +- nuttx/configs/lm3s8962-ek/nsh/setenv.sh | 2 +- nuttx/configs/lm3s8962-ek/nx/setenv.sh | 2 +- nuttx/configs/lm3s8962-ek/ostest/setenv.sh | 2 +- nuttx/configs/lpcxpresso-lpc1768/dhcpd/setenv.sh | 2 +- nuttx/configs/lpcxpresso-lpc1768/nsh/setenv.sh | 2 +- nuttx/configs/lpcxpresso-lpc1768/nx/setenv.sh | 2 +- nuttx/configs/lpcxpresso-lpc1768/ostest/setenv.sh | 2 +- nuttx/configs/lpcxpresso-lpc1768/thttpd/setenv.sh | 2 +- nuttx/configs/lpcxpresso-lpc1768/usbstorage/setenv.sh | 2 +- nuttx/configs/m68332evb/setenv.sh | 2 +- nuttx/configs/mbed/hidkbd/setenv.sh | 2 +- nuttx/configs/mbed/nsh/setenv.sh | 2 +- nuttx/configs/mcu123-lpc214x/nsh/setenv.sh | 2 +- nuttx/configs/mcu123-lpc214x/ostest/setenv.sh | 2 +- nuttx/configs/mcu123-lpc214x/usbserial/setenv.sh | 2 +- nuttx/configs/mcu123-lpc214x/usbstorage/setenv.sh | 2 +- nuttx/configs/mx1ads/ostest/setenv.sh | 2 +- nuttx/configs/ne64badge/ostest/setenv.sh | 2 +- nuttx/configs/ntosd-dm320/nettest/setenv.sh | 2 +- nuttx/configs/ntosd-dm320/nsh/setenv.sh | 2 +- nuttx/configs/ntosd-dm320/ostest/setenv.sh | 2 +- nuttx/configs/ntosd-dm320/poll/setenv.sh | 2 +- nuttx/configs/ntosd-dm320/thttpd/setenv.sh | 2 +- nuttx/configs/ntosd-dm320/udp/setenv.sh | 2 +- nuttx/configs/ntosd-dm320/uip/setenv.sh | 2 +- nuttx/configs/nucleus2g/nsh/setenv.sh | 2 +- nuttx/configs/nucleus2g/ostest/setenv.sh | 2 +- nuttx/configs/nucleus2g/usbserial/setenv.sh | 2 +- nuttx/configs/nucleus2g/usbstorage/setenv.sh | 2 +- nuttx/configs/olimex-lpc1766stk/ftpc/setenv.sh | 2 +- nuttx/configs/olimex-lpc1766stk/hidkbd/setenv.sh | 2 +- nuttx/configs/olimex-lpc1766stk/nettest/setenv.sh | 2 +- nuttx/configs/olimex-lpc1766stk/nsh/setenv.sh | 2 +- nuttx/configs/olimex-lpc1766stk/nx/setenv.sh | 2 +- nuttx/configs/olimex-lpc1766stk/ostest/setenv.sh | 2 +- nuttx/configs/olimex-lpc1766stk/slip-httpd/setenv.sh | 2 +- nuttx/configs/olimex-lpc1766stk/thttpd/setenv.sh | 2 +- nuttx/configs/olimex-lpc1766stk/usbserial/setenv.sh | 2 +- nuttx/configs/olimex-lpc1766stk/usbstorage/setenv.sh | 2 +- nuttx/configs/olimex-lpc1766stk/wlan/setenv.sh | 2 +- nuttx/configs/olimex-lpc2378/nsh/setenv.sh | 2 +- nuttx/configs/olimex-lpc2378/ostest/setenv.sh | 2 +- nuttx/configs/olimex-strp711/nettest/setenv.sh | 2 +- nuttx/configs/olimex-strp711/nsh/setenv.sh | 2 +- nuttx/configs/olimex-strp711/ostest/setenv.sh | 2 +- nuttx/configs/qemu-i486/nsh/setenv.sh | 2 +- nuttx/configs/qemu-i486/ostest/setenv.sh | 2 +- nuttx/configs/sam3u-ek/knsh/setenv.sh | 2 +- nuttx/configs/sam3u-ek/nsh/setenv.sh | 2 +- nuttx/configs/sam3u-ek/nx/setenv.sh | 2 +- nuttx/configs/sam3u-ek/ostest/setenv.sh | 2 +- nuttx/configs/sam3u-ek/touchscreen/setenv.sh | 2 +- nuttx/configs/skp16c26/ostest/setenv.sh | 2 +- nuttx/configs/stm3210e-eval/RIDE/setenv.sh | 2 +- nuttx/configs/stm3210e-eval/buttons/setenv.sh | 2 +- nuttx/configs/stm3210e-eval/nsh/setenv.sh | 2 +- nuttx/configs/stm3210e-eval/nxlines/setenv.sh | 2 +- nuttx/configs/stm3210e-eval/ostest/setenv.sh | 2 +- nuttx/configs/stm3210e-eval/usbserial/setenv.sh | 2 +- nuttx/configs/stm3210e-eval/usbstorage/setenv.sh | 2 +- nuttx/configs/stm3220g-eval/nsh/setenv.sh | 2 +- nuttx/configs/stm3220g-eval/nsh2/setenv.sh | 2 +- nuttx/configs/stm3220g-eval/nxwm/setenv.sh | 2 +- nuttx/configs/us7032evb1/nsh/setenv.sh | 2 +- nuttx/configs/us7032evb1/ostest/setenv.sh | 2 +- nuttx/configs/vsn/nsh/setenv.sh | 2 +- 94 files changed, 94 insertions(+), 94 deletions(-) (limited to 'nuttx') diff --git a/nuttx/configs/c5471evm/httpd/setenv.sh b/nuttx/configs/c5471evm/httpd/setenv.sh index e9ab8023a..0266456ff 100755 --- a/nuttx/configs/c5471evm/httpd/setenv.sh +++ b/nuttx/configs/c5471evm/httpd/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi WD=`pwd` -export BUILDROOT_BIN=${WD}/../buildroot/build_arm_nofpu/staging_dir/bin +export BUILDROOT_BIN=${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin export PATH=${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG} echo "PATH : ${PATH}" diff --git a/nuttx/configs/c5471evm/nettest/setenv.sh b/nuttx/configs/c5471evm/nettest/setenv.sh index 67bcbc1f6..403b92333 100755 --- a/nuttx/configs/c5471evm/nettest/setenv.sh +++ b/nuttx/configs/c5471evm/nettest/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi WD=`pwd` -export BUILDROOT_BIN=${WD}/../buildroot/build_arm_nofpu/staging_dir/bin +export BUILDROOT_BIN=${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin export PATH=${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG} echo "PATH : ${PATH}" diff --git a/nuttx/configs/c5471evm/nsh/setenv.sh b/nuttx/configs/c5471evm/nsh/setenv.sh index 0693ede0a..d5be870e6 100755 --- a/nuttx/configs/c5471evm/nsh/setenv.sh +++ b/nuttx/configs/c5471evm/nsh/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi WD=`pwd` -export BUILDROOT_BIN=${WD}/../buildroot/build_arm_nofpu/staging_dir/bin +export BUILDROOT_BIN=${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin export PATH=${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG} echo "PATH : ${PATH}" diff --git a/nuttx/configs/c5471evm/ostest/setenv.sh b/nuttx/configs/c5471evm/ostest/setenv.sh index e48437a41..bfe9d48c2 100755 --- a/nuttx/configs/c5471evm/ostest/setenv.sh +++ b/nuttx/configs/c5471evm/ostest/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi WD=`pwd` -export BUILDROOT_BIN=${WD}/../buildroot/build_arm_nofpu/staging_dir/bin +export BUILDROOT_BIN=${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin export PATH=${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG} echo "PATH : ${PATH}" diff --git a/nuttx/configs/compal_e88/nsh_highram/setenv.sh b/nuttx/configs/compal_e88/nsh_highram/setenv.sh index 0693ede0a..d5be870e6 100644 --- a/nuttx/configs/compal_e88/nsh_highram/setenv.sh +++ b/nuttx/configs/compal_e88/nsh_highram/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi WD=`pwd` -export BUILDROOT_BIN=${WD}/../buildroot/build_arm_nofpu/staging_dir/bin +export BUILDROOT_BIN=${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin export PATH=${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG} echo "PATH : ${PATH}" diff --git a/nuttx/configs/compal_e99/nsh_compalram/setenv.sh b/nuttx/configs/compal_e99/nsh_compalram/setenv.sh index 0693ede0a..d5be870e6 100644 --- a/nuttx/configs/compal_e99/nsh_compalram/setenv.sh +++ b/nuttx/configs/compal_e99/nsh_compalram/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi WD=`pwd` -export BUILDROOT_BIN=${WD}/../buildroot/build_arm_nofpu/staging_dir/bin +export BUILDROOT_BIN=${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin export PATH=${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG} echo "PATH : ${PATH}" diff --git a/nuttx/configs/compal_e99/nsh_highram/setenv.sh b/nuttx/configs/compal_e99/nsh_highram/setenv.sh index 0693ede0a..d5be870e6 100644 --- a/nuttx/configs/compal_e99/nsh_highram/setenv.sh +++ b/nuttx/configs/compal_e99/nsh_highram/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi WD=`pwd` -export BUILDROOT_BIN=${WD}/../buildroot/build_arm_nofpu/staging_dir/bin +export BUILDROOT_BIN=${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin export PATH=${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG} echo "PATH : ${PATH}" diff --git a/nuttx/configs/demo9s12ne64/ostest/setenv.sh b/nuttx/configs/demo9s12ne64/ostest/setenv.sh index 8f47650ca..b78b638a3 100755 --- a/nuttx/configs/demo9s12ne64/ostest/setenv.sh +++ b/nuttx/configs/demo9s12ne64/ostest/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_m9s12x/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_m9s12x/staging_dir/bin" export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/eagle100/httpd/setenv.sh b/nuttx/configs/eagle100/httpd/setenv.sh index e17655b0a..9022695a4 100755 --- a/nuttx/configs/eagle100/httpd/setenv.sh +++ b/nuttx/configs/eagle100/httpd/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/eagle100/nettest/setenv.sh b/nuttx/configs/eagle100/nettest/setenv.sh index ce89c68aa..f03beff85 100755 --- a/nuttx/configs/eagle100/nettest/setenv.sh +++ b/nuttx/configs/eagle100/nettest/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/eagle100/nsh/setenv.sh b/nuttx/configs/eagle100/nsh/setenv.sh index 93396cb73..c64bfed54 100755 --- a/nuttx/configs/eagle100/nsh/setenv.sh +++ b/nuttx/configs/eagle100/nsh/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/eagle100/nxflat/setenv.sh b/nuttx/configs/eagle100/nxflat/setenv.sh index 39afe386f..2335de190 100755 --- a/nuttx/configs/eagle100/nxflat/setenv.sh +++ b/nuttx/configs/eagle100/nxflat/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/eagle100/ostest/setenv.sh b/nuttx/configs/eagle100/ostest/setenv.sh index c3c1f581d..843f4283a 100755 --- a/nuttx/configs/eagle100/ostest/setenv.sh +++ b/nuttx/configs/eagle100/ostest/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/eagle100/thttpd/setenv.sh b/nuttx/configs/eagle100/thttpd/setenv.sh index 4dc148e65..1217e85fe 100755 --- a/nuttx/configs/eagle100/thttpd/setenv.sh +++ b/nuttx/configs/eagle100/thttpd/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/ekk-lm3s9b96/nsh/setenv.sh b/nuttx/configs/ekk-lm3s9b96/nsh/setenv.sh index 568615fa3..6e591e0dd 100755 --- a/nuttx/configs/ekk-lm3s9b96/nsh/setenv.sh +++ b/nuttx/configs/ekk-lm3s9b96/nsh/setenv.sh @@ -51,7 +51,7 @@ fi # TOOLCHAIN_BIN must be defined to the full path to the location where you # have installed the toolchain of your choice. Modify the following: -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" # Andd add the toolchain path to the PATH variable diff --git a/nuttx/configs/ekk-lm3s9b96/ostest/setenv.sh b/nuttx/configs/ekk-lm3s9b96/ostest/setenv.sh index a5e320cf6..d98c6cc40 100755 --- a/nuttx/configs/ekk-lm3s9b96/ostest/setenv.sh +++ b/nuttx/configs/ekk-lm3s9b96/ostest/setenv.sh @@ -51,7 +51,7 @@ fi # TOOLCHAIN_BIN must be defined to the full path to the location where you # have installed the toolchain of your choice. Modify the following: -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" # Andd add the toolchain path to the PATH variable diff --git a/nuttx/configs/hymini-stm32v/buttons/setenv.sh b/nuttx/configs/hymini-stm32v/buttons/setenv.sh index df0dba318..b62f59c96 100755 --- a/nuttx/configs/hymini-stm32v/buttons/setenv.sh +++ b/nuttx/configs/hymini-stm32v/buttons/setenv.sh @@ -41,7 +41,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin" -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/hymini-stm32v/nsh/setenv.sh b/nuttx/configs/hymini-stm32v/nsh/setenv.sh index a0371cdce..629897058 100755 --- a/nuttx/configs/hymini-stm32v/nsh/setenv.sh +++ b/nuttx/configs/hymini-stm32v/nsh/setenv.sh @@ -41,7 +41,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin" -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/hymini-stm32v/nxlines/setenv.sh b/nuttx/configs/hymini-stm32v/nxlines/setenv.sh index 53ccb2d0f..2027fbac9 100755 --- a/nuttx/configs/hymini-stm32v/nxlines/setenv.sh +++ b/nuttx/configs/hymini-stm32v/nxlines/setenv.sh @@ -47,7 +47,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/hymini-stm32v/usbserial/setenv.sh b/nuttx/configs/hymini-stm32v/usbserial/setenv.sh index 6b324148d..a334f1c3c 100755 --- a/nuttx/configs/hymini-stm32v/usbserial/setenv.sh +++ b/nuttx/configs/hymini-stm32v/usbserial/setenv.sh @@ -41,7 +41,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin" -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/hymini-stm32v/usbstorage/setenv.sh b/nuttx/configs/hymini-stm32v/usbstorage/setenv.sh index a0371cdce..629897058 100755 --- a/nuttx/configs/hymini-stm32v/usbstorage/setenv.sh +++ b/nuttx/configs/hymini-stm32v/usbstorage/setenv.sh @@ -41,7 +41,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin" -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/lincoln60/nsh/setenv.sh b/nuttx/configs/lincoln60/nsh/setenv.sh index ef3ca7f67..ffa6420b9 100755 --- a/nuttx/configs/lincoln60/nsh/setenv.sh +++ b/nuttx/configs/lincoln60/nsh/setenv.sh @@ -50,7 +50,7 @@ fi # TOOLCHAIN_BIN must be defined to the full path to the location where you # have installed the toolchain of your choice. Modify the following: -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" # Andd add the toolchain path to the PATH variable diff --git a/nuttx/configs/lincoln60/ostest/setenv.sh b/nuttx/configs/lincoln60/ostest/setenv.sh index 19c43760f..c0bf7c705 100755 --- a/nuttx/configs/lincoln60/ostest/setenv.sh +++ b/nuttx/configs/lincoln60/ostest/setenv.sh @@ -50,7 +50,7 @@ fi # TOOLCHAIN_BIN must be defined to the full path to the location where you # have installed the toolchain of your choice. Modify the following: -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" # Andd add the toolchain path to the PATH variable diff --git a/nuttx/configs/lm3s6432-s2e/nsh/setenv.sh b/nuttx/configs/lm3s6432-s2e/nsh/setenv.sh index 3cd011f12..5abb6085a 100644 --- a/nuttx/configs/lm3s6432-s2e/nsh/setenv.sh +++ b/nuttx/configs/lm3s6432-s2e/nsh/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/lm3s6432-s2e/ostest/setenv.sh b/nuttx/configs/lm3s6432-s2e/ostest/setenv.sh index 2cccdc70e..d680306a2 100644 --- a/nuttx/configs/lm3s6432-s2e/ostest/setenv.sh +++ b/nuttx/configs/lm3s6432-s2e/ostest/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/lm3s6965-ek/nsh/setenv.sh b/nuttx/configs/lm3s6965-ek/nsh/setenv.sh index 0b9389f49..0636f2fed 100755 --- a/nuttx/configs/lm3s6965-ek/nsh/setenv.sh +++ b/nuttx/configs/lm3s6965-ek/nsh/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/lm3s6965-ek/nx/setenv.sh b/nuttx/configs/lm3s6965-ek/nx/setenv.sh index a364c2017..3edb2710e 100755 --- a/nuttx/configs/lm3s6965-ek/nx/setenv.sh +++ b/nuttx/configs/lm3s6965-ek/nx/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/lm3s6965-ek/ostest/setenv.sh b/nuttx/configs/lm3s6965-ek/ostest/setenv.sh index 6e907ae7a..686a61701 100755 --- a/nuttx/configs/lm3s6965-ek/ostest/setenv.sh +++ b/nuttx/configs/lm3s6965-ek/ostest/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/lm3s8962-ek/nsh/setenv.sh b/nuttx/configs/lm3s8962-ek/nsh/setenv.sh index 4ed5385b6..511552d94 100755 --- a/nuttx/configs/lm3s8962-ek/nsh/setenv.sh +++ b/nuttx/configs/lm3s8962-ek/nsh/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/lm3s8962-ek/nx/setenv.sh b/nuttx/configs/lm3s8962-ek/nx/setenv.sh index 4c76fd736..a36725083 100755 --- a/nuttx/configs/lm3s8962-ek/nx/setenv.sh +++ b/nuttx/configs/lm3s8962-ek/nx/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/lm3s8962-ek/ostest/setenv.sh b/nuttx/configs/lm3s8962-ek/ostest/setenv.sh index b5ee8be31..6bd49b6fa 100755 --- a/nuttx/configs/lm3s8962-ek/ostest/setenv.sh +++ b/nuttx/configs/lm3s8962-ek/ostest/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/lpcxpresso-lpc1768/dhcpd/setenv.sh b/nuttx/configs/lpcxpresso-lpc1768/dhcpd/setenv.sh index 03641fd61..8fd20167a 100755 --- a/nuttx/configs/lpcxpresso-lpc1768/dhcpd/setenv.sh +++ b/nuttx/configs/lpcxpresso-lpc1768/dhcpd/setenv.sh @@ -42,7 +42,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` # This is where the buildroot might reside on a Linux or Cygwin system -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +# export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" # This is the default install location for Code Red on Linux export TOOLCHAIN_BIN="/usr/local/LPCXpresso/tools/bin" diff --git a/nuttx/configs/lpcxpresso-lpc1768/nsh/setenv.sh b/nuttx/configs/lpcxpresso-lpc1768/nsh/setenv.sh index 46d5b3261..8ef062805 100755 --- a/nuttx/configs/lpcxpresso-lpc1768/nsh/setenv.sh +++ b/nuttx/configs/lpcxpresso-lpc1768/nsh/setenv.sh @@ -42,7 +42,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` # This is where the buildroot might reside on a Linux or Cygwin system -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +# export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" # This is the default install location for Code Red on Linux export TOOLCHAIN_BIN="/usr/local/LPCXpresso/tools/bin" diff --git a/nuttx/configs/lpcxpresso-lpc1768/nx/setenv.sh b/nuttx/configs/lpcxpresso-lpc1768/nx/setenv.sh index 2f04a8ac6..565c16b98 100755 --- a/nuttx/configs/lpcxpresso-lpc1768/nx/setenv.sh +++ b/nuttx/configs/lpcxpresso-lpc1768/nx/setenv.sh @@ -42,7 +42,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` # This is where the buildroot might reside on a Linux or Cygwin system -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +# export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" # This is the default install location for Code Red on Linux export TOOLCHAIN_BIN="/usr/local/LPCXpresso/tools/bin" diff --git a/nuttx/configs/lpcxpresso-lpc1768/ostest/setenv.sh b/nuttx/configs/lpcxpresso-lpc1768/ostest/setenv.sh index 724d1420d..47e7468c3 100755 --- a/nuttx/configs/lpcxpresso-lpc1768/ostest/setenv.sh +++ b/nuttx/configs/lpcxpresso-lpc1768/ostest/setenv.sh @@ -42,7 +42,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` # This is where the buildroot might reside on a Linux or Cygwin system -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +# export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" # This is the default install location for Code Red on Linux export TOOLCHAIN_BIN="/usr/local/LPCXpresso/tools/bin" diff --git a/nuttx/configs/lpcxpresso-lpc1768/thttpd/setenv.sh b/nuttx/configs/lpcxpresso-lpc1768/thttpd/setenv.sh index 7156a371d..e6aded0f4 100755 --- a/nuttx/configs/lpcxpresso-lpc1768/thttpd/setenv.sh +++ b/nuttx/configs/lpcxpresso-lpc1768/thttpd/setenv.sh @@ -44,7 +44,7 @@ WD=`pwd` # This is where the buildroot might reside on a Linux or Cygwin system # A minimal buildroot version with the NXFLAT tools is always required # for this configuration in order to buildthe THTTPD CGI programs -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" # This is the default install location for Code Red on Linux export TOOLCHAIN_BIN="/usr/local/LPCXpresso/tools/bin" diff --git a/nuttx/configs/lpcxpresso-lpc1768/usbstorage/setenv.sh b/nuttx/configs/lpcxpresso-lpc1768/usbstorage/setenv.sh index 8c4039ddd..7318183ac 100755 --- a/nuttx/configs/lpcxpresso-lpc1768/usbstorage/setenv.sh +++ b/nuttx/configs/lpcxpresso-lpc1768/usbstorage/setenv.sh @@ -42,7 +42,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` # This is where the buildroot might reside on a Linux or Cygwin system -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +# export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" # This is the default install location for Code Red on Linux export TOOLCHAIN_BIN="/usr/local/LPCXpresso/tools/bin" diff --git a/nuttx/configs/m68332evb/setenv.sh b/nuttx/configs/m68332evb/setenv.sh index 2882011fd..4b52986d3 100755 --- a/nuttx/configs/m68332evb/setenv.sh +++ b/nuttx/configs/m68332evb/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi WD=`pwd` -export BUILDROOT_BIN=${WD}/../buildroot/build_m68k/staging_dir/bin +export BUILDROOT_BIN=${WD}/../misc/buildroot/build_m68k/staging_dir/bin export PATH=${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG} echo "PATH : ${PATH}" diff --git a/nuttx/configs/mbed/hidkbd/setenv.sh b/nuttx/configs/mbed/hidkbd/setenv.sh index c3ca070e3..8c14957c8 100644 --- a/nuttx/configs/mbed/hidkbd/setenv.sh +++ b/nuttx/configs/mbed/hidkbd/setenv.sh @@ -41,7 +41,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` export LPCTOOL_DIR="${WD}/configs/mbed/tools" -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/mbed/nsh/setenv.sh b/nuttx/configs/mbed/nsh/setenv.sh index f29d97589..f591fafb1 100755 --- a/nuttx/configs/mbed/nsh/setenv.sh +++ b/nuttx/configs/mbed/nsh/setenv.sh @@ -41,7 +41,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` export LPCTOOL_DIR="${WD}/configs/mbed/tools" -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/mcu123-lpc214x/nsh/setenv.sh b/nuttx/configs/mcu123-lpc214x/nsh/setenv.sh index 97295dbd7..aeb299888 100755 --- a/nuttx/configs/mcu123-lpc214x/nsh/setenv.sh +++ b/nuttx/configs/mcu123-lpc214x/nsh/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export LPC214XSCRIPTS="$WD/configs/mcu123-lpc214x/scripts" export PATH="${BUILDROOT_BIN}:${LPC214XSCRIPTS}:/sbin:/usr/sbin:${PATH_ORIG}" diff --git a/nuttx/configs/mcu123-lpc214x/ostest/setenv.sh b/nuttx/configs/mcu123-lpc214x/ostest/setenv.sh index 67d8b5d65..e71f10f88 100755 --- a/nuttx/configs/mcu123-lpc214x/ostest/setenv.sh +++ b/nuttx/configs/mcu123-lpc214x/ostest/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export LPC214XSCRIPTS="$WD/configs/mcu123-lpc214x/scripts" export PATH="${BUILDROOT_BIN}:${LPC214XSCRIPTS}:/sbin:/usr/sbin:${PATH_ORIG}" diff --git a/nuttx/configs/mcu123-lpc214x/usbserial/setenv.sh b/nuttx/configs/mcu123-lpc214x/usbserial/setenv.sh index 8661ee0cb..59d61b8b8 100755 --- a/nuttx/configs/mcu123-lpc214x/usbserial/setenv.sh +++ b/nuttx/configs/mcu123-lpc214x/usbserial/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export LPC214XSCRIPTS="$WD/configs/mcu123-lpc214x/scripts" export PATH="${BUILDROOT_BIN}:${LPC214XSCRIPTS}:/sbin:/usr/sbin:${PATH_ORIG}" diff --git a/nuttx/configs/mcu123-lpc214x/usbstorage/setenv.sh b/nuttx/configs/mcu123-lpc214x/usbstorage/setenv.sh index f27530656..7ea83ccb6 100755 --- a/nuttx/configs/mcu123-lpc214x/usbstorage/setenv.sh +++ b/nuttx/configs/mcu123-lpc214x/usbstorage/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export LPC214XSCRIPTS="$WD/configs/mcu123-lpc214x/scripts" export PATH="${BUILDROOT_BIN}:${LPC214XSCRIPTS}:/sbin:/usr/sbin:${PATH_ORIG}" diff --git a/nuttx/configs/mx1ads/ostest/setenv.sh b/nuttx/configs/mx1ads/ostest/setenv.sh index e73858fc7..a6fb5b02a 100755 --- a/nuttx/configs/mx1ads/ostest/setenv.sh +++ b/nuttx/configs/mx1ads/ostest/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi WD=`pwd` -export BUILDROOT_BIN=${WD}/../buildroot/build_arm_nofpu/staging_dir/bin +export BUILDROOT_BIN=${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin export PATH=${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG} echo "PATH : ${PATH}" diff --git a/nuttx/configs/ne64badge/ostest/setenv.sh b/nuttx/configs/ne64badge/ostest/setenv.sh index c5aa591b4..c4d6800ed 100755 --- a/nuttx/configs/ne64badge/ostest/setenv.sh +++ b/nuttx/configs/ne64badge/ostest/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_m9s12x/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_m9s12x/staging_dir/bin" export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/ntosd-dm320/nettest/setenv.sh b/nuttx/configs/ntosd-dm320/nettest/setenv.sh index 8a7788cfd..6090d4cea 100755 --- a/nuttx/configs/ntosd-dm320/nettest/setenv.sh +++ b/nuttx/configs/ntosd-dm320/nettest/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi WD=`pwd` -export BUILDROOT_BIN=${WD}/../buildroot/build_arm_nofpu/staging_dir/bin +export BUILDROOT_BIN=${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin export PATH=${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG} echo "PATH : ${PATH}" diff --git a/nuttx/configs/ntosd-dm320/nsh/setenv.sh b/nuttx/configs/ntosd-dm320/nsh/setenv.sh index bf3f497ad..a84e68884 100755 --- a/nuttx/configs/ntosd-dm320/nsh/setenv.sh +++ b/nuttx/configs/ntosd-dm320/nsh/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi WD=`pwd` -export BUILDROOT_BIN=${WD}/../buildroot/build_arm_nofpu/staging_dir/bin +export BUILDROOT_BIN=${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin export PATH=${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG} echo "PATH : ${PATH}" diff --git a/nuttx/configs/ntosd-dm320/ostest/setenv.sh b/nuttx/configs/ntosd-dm320/ostest/setenv.sh index 6ce1e04a8..a65be2677 100755 --- a/nuttx/configs/ntosd-dm320/ostest/setenv.sh +++ b/nuttx/configs/ntosd-dm320/ostest/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi WD=`pwd` -export BUILDROOT_BIN=${WD}/../buildroot/build_arm_nofpu/staging_dir/bin +export BUILDROOT_BIN=${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin export PATH=${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG} echo "PATH : ${PATH}" diff --git a/nuttx/configs/ntosd-dm320/poll/setenv.sh b/nuttx/configs/ntosd-dm320/poll/setenv.sh index a3479fb18..de3b64ea9 100755 --- a/nuttx/configs/ntosd-dm320/poll/setenv.sh +++ b/nuttx/configs/ntosd-dm320/poll/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi WD=`pwd` -export BUILDROOT_BIN=${WD}/../buildroot/build_arm_nofpu/staging_dir/bin +export BUILDROOT_BIN=${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin export PATH=${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG} echo "PATH : ${PATH}" diff --git a/nuttx/configs/ntosd-dm320/thttpd/setenv.sh b/nuttx/configs/ntosd-dm320/thttpd/setenv.sh index 54700fb6b..92ff91700 100755 --- a/nuttx/configs/ntosd-dm320/thttpd/setenv.sh +++ b/nuttx/configs/ntosd-dm320/thttpd/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi WD=`pwd` -export BUILDROOT_BIN=${WD}/../buildroot/build_arm_nofpu/staging_dir/bin +export BUILDROOT_BIN=${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin export PATH=${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG} echo "PATH : ${PATH}" diff --git a/nuttx/configs/ntosd-dm320/udp/setenv.sh b/nuttx/configs/ntosd-dm320/udp/setenv.sh index a2e1ffec7..052413b08 100755 --- a/nuttx/configs/ntosd-dm320/udp/setenv.sh +++ b/nuttx/configs/ntosd-dm320/udp/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi WD=`pwd` -export BUILDROOT_BIN=${WD}/../buildroot/build_arm_nofpu/staging_dir/bin +export BUILDROOT_BIN=${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin export PATH=${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG} echo "PATH : ${PATH}" diff --git a/nuttx/configs/ntosd-dm320/uip/setenv.sh b/nuttx/configs/ntosd-dm320/uip/setenv.sh index ccc74829d..988e0a126 100755 --- a/nuttx/configs/ntosd-dm320/uip/setenv.sh +++ b/nuttx/configs/ntosd-dm320/uip/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi WD=`pwd` -export BUILDROOT_BIN=${WD}/../buildroot/build_arm_nofpu/staging_dir/bin +export BUILDROOT_BIN=${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin export PATH=${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG} echo "PATH : ${PATH}" diff --git a/nuttx/configs/nucleus2g/nsh/setenv.sh b/nuttx/configs/nucleus2g/nsh/setenv.sh index ffdc74e9b..977e0d474 100755 --- a/nuttx/configs/nucleus2g/nsh/setenv.sh +++ b/nuttx/configs/nucleus2g/nsh/setenv.sh @@ -41,7 +41,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` export LPCTOOL_DIR="${WD}/configs/nucleus2g/tools" -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/nucleus2g/ostest/setenv.sh b/nuttx/configs/nucleus2g/ostest/setenv.sh index 6a78a5c23..d52412b4b 100755 --- a/nuttx/configs/nucleus2g/ostest/setenv.sh +++ b/nuttx/configs/nucleus2g/ostest/setenv.sh @@ -41,7 +41,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` export LPCTOOL_DIR="${WD}/configs/nucleus2g/tools" -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/nucleus2g/usbserial/setenv.sh b/nuttx/configs/nucleus2g/usbserial/setenv.sh index 9333b3a2f..cbd2e8d81 100755 --- a/nuttx/configs/nucleus2g/usbserial/setenv.sh +++ b/nuttx/configs/nucleus2g/usbserial/setenv.sh @@ -41,7 +41,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` export LPCTOOL_DIR="${WD}/configs/nucleus2g/tools" -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/nucleus2g/usbstorage/setenv.sh b/nuttx/configs/nucleus2g/usbstorage/setenv.sh index e6f7197fd..2443be4e1 100755 --- a/nuttx/configs/nucleus2g/usbstorage/setenv.sh +++ b/nuttx/configs/nucleus2g/usbstorage/setenv.sh @@ -41,7 +41,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` export LPCTOOL_DIR="${WD}/configs/nucleus2g/tools" -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/olimex-lpc1766stk/ftpc/setenv.sh b/nuttx/configs/olimex-lpc1766stk/ftpc/setenv.sh index 85d20db32..df1091690 100755 --- a/nuttx/configs/olimex-lpc1766stk/ftpc/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/ftpc/setenv.sh @@ -41,7 +41,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools" -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/olimex-lpc1766stk/hidkbd/setenv.sh b/nuttx/configs/olimex-lpc1766stk/hidkbd/setenv.sh index 7bdba25d7..e4e130c24 100755 --- a/nuttx/configs/olimex-lpc1766stk/hidkbd/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/hidkbd/setenv.sh @@ -41,7 +41,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools" -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/olimex-lpc1766stk/nettest/setenv.sh b/nuttx/configs/olimex-lpc1766stk/nettest/setenv.sh index 58951dc84..92c6bdf5e 100755 --- a/nuttx/configs/olimex-lpc1766stk/nettest/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/nettest/setenv.sh @@ -41,7 +41,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools" -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/olimex-lpc1766stk/nsh/setenv.sh b/nuttx/configs/olimex-lpc1766stk/nsh/setenv.sh index 4b9bec6d0..089165f69 100755 --- a/nuttx/configs/olimex-lpc1766stk/nsh/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/nsh/setenv.sh @@ -41,7 +41,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools" -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/olimex-lpc1766stk/nx/setenv.sh b/nuttx/configs/olimex-lpc1766stk/nx/setenv.sh index a2027d727..69cee3997 100755 --- a/nuttx/configs/olimex-lpc1766stk/nx/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/nx/setenv.sh @@ -41,7 +41,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools" -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/olimex-lpc1766stk/ostest/setenv.sh b/nuttx/configs/olimex-lpc1766stk/ostest/setenv.sh index 996cefc4e..b61805da0 100755 --- a/nuttx/configs/olimex-lpc1766stk/ostest/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/ostest/setenv.sh @@ -41,7 +41,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools" -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/olimex-lpc1766stk/slip-httpd/setenv.sh b/nuttx/configs/olimex-lpc1766stk/slip-httpd/setenv.sh index 546ca1e3a..50364e4a1 100755 --- a/nuttx/configs/olimex-lpc1766stk/slip-httpd/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/slip-httpd/setenv.sh @@ -41,7 +41,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools" -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/olimex-lpc1766stk/thttpd/setenv.sh b/nuttx/configs/olimex-lpc1766stk/thttpd/setenv.sh index 09288f04c..2a9ddae15 100755 --- a/nuttx/configs/olimex-lpc1766stk/thttpd/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/thttpd/setenv.sh @@ -41,7 +41,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools" -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/olimex-lpc1766stk/usbserial/setenv.sh b/nuttx/configs/olimex-lpc1766stk/usbserial/setenv.sh index f755b6afe..b12d65852 100755 --- a/nuttx/configs/olimex-lpc1766stk/usbserial/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/usbserial/setenv.sh @@ -41,7 +41,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools" -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/olimex-lpc1766stk/usbstorage/setenv.sh b/nuttx/configs/olimex-lpc1766stk/usbstorage/setenv.sh index e41283c43..58fd5d04d 100755 --- a/nuttx/configs/olimex-lpc1766stk/usbstorage/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/usbstorage/setenv.sh @@ -41,7 +41,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools" -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/olimex-lpc1766stk/wlan/setenv.sh b/nuttx/configs/olimex-lpc1766stk/wlan/setenv.sh index 1b87dab69..6e6c79ab2 100755 --- a/nuttx/configs/olimex-lpc1766stk/wlan/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/wlan/setenv.sh @@ -41,7 +41,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools" -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/olimex-lpc2378/nsh/setenv.sh b/nuttx/configs/olimex-lpc2378/nsh/setenv.sh index 9a2e92e43..15808d32b 100755 --- a/nuttx/configs/olimex-lpc2378/nsh/setenv.sh +++ b/nuttx/configs/olimex-lpc2378/nsh/setenv.sh @@ -45,7 +45,7 @@ fi if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export LPC23XXSCRIPTS="$WD/configs/olimex-lpc2378/scripts" export PATH="${BUILDROOT_BIN}:${LPC23XXSCRIPTS}:/sbin:/usr/sbin:${PATH_ORIG}" diff --git a/nuttx/configs/olimex-lpc2378/ostest/setenv.sh b/nuttx/configs/olimex-lpc2378/ostest/setenv.sh index 73bf3d223..9e7ff11fc 100755 --- a/nuttx/configs/olimex-lpc2378/ostest/setenv.sh +++ b/nuttx/configs/olimex-lpc2378/ostest/setenv.sh @@ -45,7 +45,7 @@ fi if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export LPC23XXSCRIPTS="$WD/configs/olimex-lpc2378/scripts" export PATH="${BUILDROOT_BIN}:${LPC23XXSCRIPTS}:/sbin:/usr/sbin:${PATH_ORIG}" diff --git a/nuttx/configs/olimex-strp711/nettest/setenv.sh b/nuttx/configs/olimex-strp711/nettest/setenv.sh index bc47c3ed8..74003581b 100755 --- a/nuttx/configs/olimex-strp711/nettest/setenv.sh +++ b/nuttx/configs/olimex-strp711/nettest/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export STR41XSCRIPTS="$WD/configs/olimex-strp711/scripts" export PATH="${BUILDROOT_BIN}:${STR41XSCRIPTS}:/sbin:/usr/sbin:${PATH_ORIG}" diff --git a/nuttx/configs/olimex-strp711/nsh/setenv.sh b/nuttx/configs/olimex-strp711/nsh/setenv.sh index 6724741f6..f6d22c1ec 100755 --- a/nuttx/configs/olimex-strp711/nsh/setenv.sh +++ b/nuttx/configs/olimex-strp711/nsh/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export STR41XSCRIPTS="$WD/configs/olimex-strp711/scripts" export PATH="${BUILDROOT_BIN}:${STR41XSCRIPTS}:/sbin:/usr/sbin:${PATH_ORIG}" diff --git a/nuttx/configs/olimex-strp711/ostest/setenv.sh b/nuttx/configs/olimex-strp711/ostest/setenv.sh index c9454d26f..f20997352 100755 --- a/nuttx/configs/olimex-strp711/ostest/setenv.sh +++ b/nuttx/configs/olimex-strp711/ostest/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export STR41XSCRIPTS="$WD/configs/olimex-strp711/scripts" export PATH="${BUILDROOT_BIN}:${STR41XSCRIPTS}:/sbin:/usr/sbin:${PATH_ORIG}" diff --git a/nuttx/configs/qemu-i486/nsh/setenv.sh b/nuttx/configs/qemu-i486/nsh/setenv.sh index 25ae59d71..5542bc4e2 100755 --- a/nuttx/configs/qemu-i486/nsh/setenv.sh +++ b/nuttx/configs/qemu-i486/nsh/setenv.sh @@ -42,7 +42,7 @@ if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi # Uncomment and modify the following if you are using anything other # than the system GCC # WD=`pwd` -# export BUILDROOT_BIN="${WD}/../../../buildroot/build_i486/staging_dir/bin" +# export BUILDROOT_BIN="${WD}/../../../misc/buildroot/build_i486/staging_dir/bin" # export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/qemu-i486/ostest/setenv.sh b/nuttx/configs/qemu-i486/ostest/setenv.sh index f9c3bdec8..a3c68d797 100755 --- a/nuttx/configs/qemu-i486/ostest/setenv.sh +++ b/nuttx/configs/qemu-i486/ostest/setenv.sh @@ -42,7 +42,7 @@ if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi # Uncomment and modify the following if you are using anything other # than the system GCC # WD=`pwd` -# export BUILDROOT_BIN="${WD}/../../../buildroot/build_i486/staging_dir/bin" +# export BUILDROOT_BIN="${WD}/../../../misc/buildroot/build_i486/staging_dir/bin" # export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/sam3u-ek/knsh/setenv.sh b/nuttx/configs/sam3u-ek/knsh/setenv.sh index 3b27c3d9f..1b8842e82 100755 --- a/nuttx/configs/sam3u-ek/knsh/setenv.sh +++ b/nuttx/configs/sam3u-ek/knsh/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/sam3u-ek/nsh/setenv.sh b/nuttx/configs/sam3u-ek/nsh/setenv.sh index 3f4e60221..ae56ecc43 100755 --- a/nuttx/configs/sam3u-ek/nsh/setenv.sh +++ b/nuttx/configs/sam3u-ek/nsh/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/sam3u-ek/nx/setenv.sh b/nuttx/configs/sam3u-ek/nx/setenv.sh index a7e9efc84..2730db642 100755 --- a/nuttx/configs/sam3u-ek/nx/setenv.sh +++ b/nuttx/configs/sam3u-ek/nx/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/sam3u-ek/ostest/setenv.sh b/nuttx/configs/sam3u-ek/ostest/setenv.sh index 06d5eb547..ab0f8bd96 100755 --- a/nuttx/configs/sam3u-ek/ostest/setenv.sh +++ b/nuttx/configs/sam3u-ek/ostest/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/sam3u-ek/touchscreen/setenv.sh b/nuttx/configs/sam3u-ek/touchscreen/setenv.sh index d5af12280..868c4de38 100755 --- a/nuttx/configs/sam3u-ek/touchscreen/setenv.sh +++ b/nuttx/configs/sam3u-ek/touchscreen/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/skp16c26/ostest/setenv.sh b/nuttx/configs/skp16c26/ostest/setenv.sh index a74258fb8..72c16064b 100755 --- a/nuttx/configs/skp16c26/ostest/setenv.sh +++ b/nuttx/configs/skp16c26/ostest/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi WD=`pwd` -export BUILDROOT_BIN=${WD}/../buildroot/build_m32c/staging_dir/bin +export BUILDROOT_BIN=${WD}/../misc/buildroot/build_m32c/staging_dir/bin export PATH=${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG} echo "PATH : ${PATH}" diff --git a/nuttx/configs/stm3210e-eval/RIDE/setenv.sh b/nuttx/configs/stm3210e-eval/RIDE/setenv.sh index b73411136..40872c164 100755 --- a/nuttx/configs/stm3210e-eval/RIDE/setenv.sh +++ b/nuttx/configs/stm3210e-eval/RIDE/setenv.sh @@ -41,7 +41,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin" -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/stm3210e-eval/buttons/setenv.sh b/nuttx/configs/stm3210e-eval/buttons/setenv.sh index 2bdf53674..0afc622fb 100755 --- a/nuttx/configs/stm3210e-eval/buttons/setenv.sh +++ b/nuttx/configs/stm3210e-eval/buttons/setenv.sh @@ -41,7 +41,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin" -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/stm3210e-eval/nsh/setenv.sh b/nuttx/configs/stm3210e-eval/nsh/setenv.sh index ee33a8d21..ff9a4bf8a 100755 --- a/nuttx/configs/stm3210e-eval/nsh/setenv.sh +++ b/nuttx/configs/stm3210e-eval/nsh/setenv.sh @@ -41,7 +41,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin" -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/stm3210e-eval/nxlines/setenv.sh b/nuttx/configs/stm3210e-eval/nxlines/setenv.sh index a9dc78c74..90e6fa05c 100755 --- a/nuttx/configs/stm3210e-eval/nxlines/setenv.sh +++ b/nuttx/configs/stm3210e-eval/nxlines/setenv.sh @@ -47,7 +47,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/stm3210e-eval/ostest/setenv.sh b/nuttx/configs/stm3210e-eval/ostest/setenv.sh index 046a7f5ac..43495b514 100755 --- a/nuttx/configs/stm3210e-eval/ostest/setenv.sh +++ b/nuttx/configs/stm3210e-eval/ostest/setenv.sh @@ -41,7 +41,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin" -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/stm3210e-eval/usbserial/setenv.sh b/nuttx/configs/stm3210e-eval/usbserial/setenv.sh index 046a7f5ac..43495b514 100755 --- a/nuttx/configs/stm3210e-eval/usbserial/setenv.sh +++ b/nuttx/configs/stm3210e-eval/usbserial/setenv.sh @@ -41,7 +41,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin" -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/stm3210e-eval/usbstorage/setenv.sh b/nuttx/configs/stm3210e-eval/usbstorage/setenv.sh index ee33a8d21..ff9a4bf8a 100755 --- a/nuttx/configs/stm3210e-eval/usbstorage/setenv.sh +++ b/nuttx/configs/stm3210e-eval/usbstorage/setenv.sh @@ -41,7 +41,7 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin" -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/stm3220g-eval/nsh/setenv.sh b/nuttx/configs/stm3220g-eval/nsh/setenv.sh index 489322177..fcec398eb 100755 --- a/nuttx/configs/stm3220g-eval/nsh/setenv.sh +++ b/nuttx/configs/stm3220g-eval/nsh/setenv.sh @@ -67,7 +67,7 @@ fi # This is the Cygwin path to the location where I build the buildroot # toolchain. -export TOOLCHAIN_BIN="${WD}/../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 variable export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" diff --git a/nuttx/configs/stm3220g-eval/nsh2/setenv.sh b/nuttx/configs/stm3220g-eval/nsh2/setenv.sh index 1e2f87b40..af7403656 100755 --- a/nuttx/configs/stm3220g-eval/nsh2/setenv.sh +++ b/nuttx/configs/stm3220g-eval/nsh2/setenv.sh @@ -66,7 +66,7 @@ fi # This is the Cygwin path to the location where I build the buildroot # toolchain. -export TOOLCHAIN_BIN="${WD}/../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 variable export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" diff --git a/nuttx/configs/stm3220g-eval/nxwm/setenv.sh b/nuttx/configs/stm3220g-eval/nxwm/setenv.sh index ff642018e..858531391 100755 --- a/nuttx/configs/stm3220g-eval/nxwm/setenv.sh +++ b/nuttx/configs/stm3220g-eval/nxwm/setenv.sh @@ -67,7 +67,7 @@ export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ # This is the Cygwin path to the location where I build the buildroot # toolchain. -export TOOLCHAIN_BIN="${WD}/../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 variable export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" diff --git a/nuttx/configs/us7032evb1/nsh/setenv.sh b/nuttx/configs/us7032evb1/nsh/setenv.sh index d23133612..fabcfb1de 100755 --- a/nuttx/configs/us7032evb1/nsh/setenv.sh +++ b/nuttx/configs/us7032evb1/nsh/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi WD=`pwd` -export BUILDROOT_BIN=${WD}/../buildroot/build_sh/staging_dir/bin +export BUILDROOT_BIN=${WD}/../misc/buildroot/build_sh/staging_dir/bin export SH1BINARIES=$WD/configs/us7032evb1/bin export PATH=${BUILDROOT_BIN}:${SH1BINARIES}:/sbin:/usr/sbin:${PATH_ORIG} diff --git a/nuttx/configs/us7032evb1/ostest/setenv.sh b/nuttx/configs/us7032evb1/ostest/setenv.sh index ac37e9150..6a923c959 100755 --- a/nuttx/configs/us7032evb1/ostest/setenv.sh +++ b/nuttx/configs/us7032evb1/ostest/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi WD=`pwd` -export BUILDROOT_BIN=${WD}/../buildroot/build_sh/staging_dir/bin +export BUILDROOT_BIN=${WD}/../misc/buildroot/build_sh/staging_dir/bin export SH1BINARIES=$WD/configs/us7032evb1/bin export PATH=${BUILDROOT_BIN}:${SH1BINARIES}:/sbin:/usr/sbin:${PATH_ORIG} diff --git a/nuttx/configs/vsn/nsh/setenv.sh b/nuttx/configs/vsn/nsh/setenv.sh index 3b9f7f896..a01a604c0 100755 --- a/nuttx/configs/vsn/nsh/setenv.sh +++ b/nuttx/configs/vsn/nsh/setenv.sh @@ -40,7 +40,7 @@ fi if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" -- cgit v1.2.3 From ed4550ff485a872b343c8e51697c9810f37e2a9a Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 10 Oct 2012 17:01:23 +0000 Subject: Rename gnu-nxflat.ld to gnu-nxflat-gotoff.ld; Add gnu-nxflat-pcrel.ld git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5225 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/Documentation/NuttXNxFlat.html | 25 ++- nuttx/TODO | 6 +- nuttx/binfmt/libnxflat/gnu-nxflat-gotoff.ld | 182 +++++++++++++++++++++ nuttx/binfmt/libnxflat/gnu-nxflat-pcrel.ld | 182 +++++++++++++++++++++ nuttx/binfmt/libnxflat/gnu-nxflat.ld | 172 ------------------- nuttx/configs/amber/hello/Make.defs | 2 +- nuttx/configs/c5471evm/httpd/Make.defs | 2 +- nuttx/configs/c5471evm/nettest/Make.defs | 2 +- nuttx/configs/c5471evm/nsh/Make.defs | 2 +- nuttx/configs/c5471evm/ostest/Make.defs | 2 +- nuttx/configs/compal_e88/nsh_highram/Make.defs | 2 +- nuttx/configs/compal_e99/nsh_compalram/Make.defs | 2 +- nuttx/configs/compal_e99/nsh_highram/Make.defs | 2 +- nuttx/configs/demo9s12ne64/ostest/Make.defs | 2 +- nuttx/configs/ea3131/nsh/Make.defs | 2 +- nuttx/configs/ea3131/ostest/Make.defs | 2 +- nuttx/configs/ea3131/pgnsh/Make.defs | 2 +- nuttx/configs/ea3131/usbserial/Make.defs | 2 +- nuttx/configs/ea3131/usbstorage/Make.defs | 2 +- nuttx/configs/ea3152/ostest/Make.defs | 2 +- nuttx/configs/eagle100/README.txt | 4 +- nuttx/configs/eagle100/httpd/Make.defs | 2 +- nuttx/configs/eagle100/nettest/Make.defs | 2 +- nuttx/configs/eagle100/nsh/Make.defs | 2 +- nuttx/configs/eagle100/nxflat/Make.defs | 2 +- nuttx/configs/eagle100/ostest/Make.defs | 2 +- nuttx/configs/eagle100/thttpd/Make.defs | 2 +- nuttx/configs/ekk-lm3s9b96/README.txt | 4 +- nuttx/configs/ekk-lm3s9b96/nsh/Make.defs | 2 +- nuttx/configs/ekk-lm3s9b96/ostest/Make.defs | 2 +- nuttx/configs/fire-stm32v2/README.txt | 4 +- nuttx/configs/fire-stm32v2/nsh/Make.defs | 2 +- nuttx/configs/hymini-stm32v/README.txt | 4 +- nuttx/configs/hymini-stm32v/buttons/Make.defs | 2 +- nuttx/configs/hymini-stm32v/nsh/Make.defs | 2 +- nuttx/configs/hymini-stm32v/nsh2/Make.defs | 2 +- nuttx/configs/hymini-stm32v/nx/Make.defs | 2 +- nuttx/configs/hymini-stm32v/nxlines/Make.defs | 2 +- nuttx/configs/hymini-stm32v/usbserial/Make.defs | 2 +- nuttx/configs/hymini-stm32v/usbstorage/Make.defs | 2 +- nuttx/configs/kwikstik-k40/README.txt | 4 +- nuttx/configs/kwikstik-k40/ostest/Make.defs | 2 +- nuttx/configs/lincoln60/README.txt | 4 +- nuttx/configs/lincoln60/nsh/Make.defs | 2 +- nuttx/configs/lincoln60/ostest/Make.defs | 2 +- nuttx/configs/lm3s6432-s2e/README.txt | 4 +- nuttx/configs/lm3s6432-s2e/nsh/Make.defs | 2 +- nuttx/configs/lm3s6432-s2e/ostest/Make.defs | 2 +- nuttx/configs/lm3s6965-ek/README.txt | 4 +- nuttx/configs/lm3s6965-ek/nsh/Make.defs | 2 +- nuttx/configs/lm3s6965-ek/nx/Make.defs | 2 +- nuttx/configs/lm3s6965-ek/ostest/Make.defs | 2 +- nuttx/configs/lm3s8962-ek/README.txt | 4 +- nuttx/configs/lm3s8962-ek/nsh/Make.defs | 2 +- nuttx/configs/lm3s8962-ek/nx/Make.defs | 2 +- nuttx/configs/lm3s8962-ek/ostest/Make.defs | 2 +- nuttx/configs/lpc4330-xplorer/README.txt | 4 +- nuttx/configs/lpc4330-xplorer/nsh/Make.defs | 2 +- nuttx/configs/lpc4330-xplorer/ostest/Make.defs | 2 +- nuttx/configs/lpcxpresso-lpc1768/README.txt | 4 +- nuttx/configs/lpcxpresso-lpc1768/dhcpd/Make.defs | 2 +- nuttx/configs/lpcxpresso-lpc1768/nsh/Make.defs | 2 +- nuttx/configs/lpcxpresso-lpc1768/nx/Make.defs | 2 +- nuttx/configs/lpcxpresso-lpc1768/ostest/Make.defs | 2 +- nuttx/configs/lpcxpresso-lpc1768/thttpd/Make.defs | 4 +- .../lpcxpresso-lpc1768/usbstorage/Make.defs | 2 +- nuttx/configs/mbed/README.txt | 4 +- nuttx/configs/mbed/hidkbd/Make.defs | 2 +- nuttx/configs/mbed/nsh/Make.defs | 2 +- nuttx/configs/mcu123-lpc214x/composite/Make.defs | 2 +- nuttx/configs/mcu123-lpc214x/nsh/Make.defs | 2 +- nuttx/configs/mcu123-lpc214x/ostest/Make.defs | 2 +- nuttx/configs/mcu123-lpc214x/usbserial/Make.defs | 2 +- nuttx/configs/mcu123-lpc214x/usbstorage/Make.defs | 2 +- nuttx/configs/micropendous3/hello/Make.defs | 2 +- nuttx/configs/mirtoo/nsh/Make.defs | 2 +- nuttx/configs/mirtoo/nxffs/Make.defs | 2 +- nuttx/configs/mirtoo/ostest/Make.defs | 2 +- nuttx/configs/mx1ads/ostest/Make.defs | 2 +- nuttx/configs/ne64badge/ostest/Make.defs | 2 +- nuttx/configs/ntosd-dm320/nettest/Make.defs | 2 +- nuttx/configs/ntosd-dm320/nsh/Make.defs | 2 +- nuttx/configs/ntosd-dm320/ostest/Make.defs | 2 +- nuttx/configs/ntosd-dm320/poll/Make.defs | 2 +- nuttx/configs/ntosd-dm320/thttpd/Make.defs | 2 +- nuttx/configs/ntosd-dm320/udp/Make.defs | 2 +- nuttx/configs/ntosd-dm320/uip/Make.defs | 2 +- nuttx/configs/nucleus2g/README.txt | 4 +- nuttx/configs/nucleus2g/nsh/Make.defs | 2 +- nuttx/configs/nucleus2g/ostest/Make.defs | 2 +- nuttx/configs/nucleus2g/usbserial/Make.defs | 2 +- nuttx/configs/nucleus2g/usbstorage/Make.defs | 2 +- nuttx/configs/olimex-lpc1766stk/README.txt | 4 +- nuttx/configs/olimex-lpc1766stk/ftpc/Make.defs | 2 +- nuttx/configs/olimex-lpc1766stk/hidkbd/Make.defs | 2 +- nuttx/configs/olimex-lpc1766stk/nettest/Make.defs | 2 +- nuttx/configs/olimex-lpc1766stk/nsh/Make.defs | 2 +- nuttx/configs/olimex-lpc1766stk/nx/Make.defs | 2 +- nuttx/configs/olimex-lpc1766stk/ostest/Make.defs | 2 +- .../configs/olimex-lpc1766stk/slip-httpd/Make.defs | 2 +- nuttx/configs/olimex-lpc1766stk/thttpd/Make.defs | 2 +- .../configs/olimex-lpc1766stk/usbserial/Make.defs | 2 +- .../configs/olimex-lpc1766stk/usbstorage/Make.defs | 2 +- nuttx/configs/olimex-lpc1766stk/wlan/Make.defs | 2 +- nuttx/configs/olimex-lpc2378/nsh/Make.defs | 2 +- nuttx/configs/olimex-lpc2378/ostest/Make.defs | 2 +- nuttx/configs/olimex-stm32-p107/nsh/Make.defs | 2 +- nuttx/configs/olimex-stm32-p107/ostest/Make.defs | 2 +- nuttx/configs/olimex-strp711/nettest/Make.defs | 2 +- nuttx/configs/olimex-strp711/nsh/Make.defs | 2 +- nuttx/configs/olimex-strp711/ostest/Make.defs | 2 +- nuttx/configs/pcblogic-pic32mx/nsh/Make.defs | 2 +- nuttx/configs/pcblogic-pic32mx/ostest/Make.defs | 2 +- nuttx/configs/pic32-starterkit/nsh/Make.defs | 2 +- nuttx/configs/pic32-starterkit/nsh2/Make.defs | 2 +- nuttx/configs/pic32-starterkit/ostest/Make.defs | 2 +- nuttx/configs/pic32mx7mmb/nsh/Make.defs | 2 +- nuttx/configs/pic32mx7mmb/ostest/Make.defs | 2 +- nuttx/configs/sam3u-ek/README.txt | 4 +- nuttx/configs/sam3u-ek/knsh/Make.defs | 2 +- nuttx/configs/sam3u-ek/nsh/Make.defs | 2 +- nuttx/configs/sam3u-ek/nx/Make.defs | 2 +- nuttx/configs/sam3u-ek/ostest/Make.defs | 2 +- nuttx/configs/sam3u-ek/touchscreen/Make.defs | 2 +- nuttx/configs/shenzhou/README.txt | 60 ++++++- nuttx/configs/shenzhou/nsh/Make.defs | 2 +- nuttx/configs/shenzhou/nxwm/Make.defs | 2 +- nuttx/configs/stm3210e-eval/README.txt | 4 +- nuttx/configs/stm3210e-eval/RIDE/Make.defs | 2 +- nuttx/configs/stm3210e-eval/buttons/Make.defs | 2 +- nuttx/configs/stm3210e-eval/composite/Make.defs | 2 +- nuttx/configs/stm3210e-eval/nsh/Make.defs | 2 +- nuttx/configs/stm3210e-eval/nsh2/Make.defs | 2 +- nuttx/configs/stm3210e-eval/nx/Make.defs | 2 +- nuttx/configs/stm3210e-eval/nxconsole/Make.defs | 2 +- nuttx/configs/stm3210e-eval/nxlines/Make.defs | 2 +- nuttx/configs/stm3210e-eval/nxtext/Make.defs | 2 +- nuttx/configs/stm3210e-eval/ostest/Make.defs | 2 +- nuttx/configs/stm3210e-eval/pm/Make.defs | 2 +- nuttx/configs/stm3210e-eval/usbserial/Make.defs | 2 +- nuttx/configs/stm3210e-eval/usbstorage/Make.defs | 2 +- nuttx/configs/stm3220g-eval/README.txt | 4 +- nuttx/configs/stm3220g-eval/dhcpd/Make.defs | 2 +- nuttx/configs/stm3220g-eval/nettest/Make.defs | 2 +- nuttx/configs/stm3220g-eval/nsh/Make.defs | 2 +- nuttx/configs/stm3220g-eval/nsh2/Make.defs | 2 +- nuttx/configs/stm3220g-eval/nxwm/Make.defs | 2 +- nuttx/configs/stm3220g-eval/ostest/Make.defs | 2 +- nuttx/configs/stm3220g-eval/telnetd/Make.defs | 2 +- nuttx/configs/stm3240g-eval/README.txt | 4 +- nuttx/configs/stm3240g-eval/dhcpd/Make.defs | 2 +- nuttx/configs/stm3240g-eval/discover/Make.defs | 2 +- nuttx/configs/stm3240g-eval/nettest/Make.defs | 2 +- nuttx/configs/stm3240g-eval/nsh/Make.defs | 2 +- nuttx/configs/stm3240g-eval/nsh2/Make.defs | 2 +- nuttx/configs/stm3240g-eval/nxconsole/Make.defs | 2 +- nuttx/configs/stm3240g-eval/nxwm/Make.defs | 2 +- nuttx/configs/stm3240g-eval/ostest/Make.defs | 2 +- nuttx/configs/stm3240g-eval/telnetd/Make.defs | 2 +- nuttx/configs/stm3240g-eval/webserver/Make.defs | 2 +- nuttx/configs/stm3240g-eval/xmlrpc/Make.defs | 2 +- nuttx/configs/stm32f4discovery/README.txt | 4 +- nuttx/configs/stm32f4discovery/nsh/Make.defs | 2 +- nuttx/configs/stm32f4discovery/nxlines/Make.defs | 2 +- nuttx/configs/stm32f4discovery/ostest/Make.defs | 2 +- nuttx/configs/stm32f4discovery/pm/Make.defs | 2 +- nuttx/configs/sure-pic32mx/nsh/Make.defs | 2 +- nuttx/configs/sure-pic32mx/ostest/Make.defs | 2 +- nuttx/configs/sure-pic32mx/usbnsh/Make.defs | 2 +- nuttx/configs/teensy/hello/Make.defs | 2 +- nuttx/configs/teensy/nsh/Make.defs | 2 +- nuttx/configs/teensy/usbstorage/Make.defs | 2 +- nuttx/configs/twr-k60n512/README.txt | 4 +- nuttx/configs/twr-k60n512/nsh/Make.defs | 2 +- nuttx/configs/twr-k60n512/ostest/Make.defs | 2 +- nuttx/configs/ubw32/nsh/Make.defs | 2 +- nuttx/configs/ubw32/ostest/Make.defs | 2 +- nuttx/configs/vsn/README.txt | 4 +- nuttx/configs/vsn/nsh/Make.defs | 2 +- 179 files changed, 662 insertions(+), 355 deletions(-) create mode 100644 nuttx/binfmt/libnxflat/gnu-nxflat-gotoff.ld create mode 100644 nuttx/binfmt/libnxflat/gnu-nxflat-pcrel.ld delete mode 100644 nuttx/binfmt/libnxflat/gnu-nxflat.ld (limited to 'nuttx') diff --git a/nuttx/Documentation/NuttXNxFlat.html b/nuttx/Documentation/NuttXNxFlat.html index 73be5d7b3..4d70ed9c3 100644 --- a/nuttx/Documentation/NuttXNxFlat.html +++ b/nuttx/Documentation/NuttXNxFlat.html @@ -229,13 +229,16 @@
                        • Read-Only Data in RAM

                            - Read-only data must reside in RAM. + With older GCC compilers (at least up to 4.3.3), read-only data must reside in RAM. In code generated by GCC, all data references are indexed by the PIC2 base register (that is usually R10 or sl for the ARM processors). The includes read-only data (.rodata). Embedded firmware developers normally like to keep .rodata in FLASH with the code sections. But because all data is referenced with the PIC base register, all of that data must lie in RAM. A NXFLAT change to work around this is under investigation3.

                            +

                            + Newer GCC compilers (at least from 4.6.3), read-only data is no long GOT-relative, but is now accessed PC-relative. With PC relative addressing, read-only data must reside in the I-Space. +

                        • Globally Scoped Function Function Pointers @@ -464,7 +467,7 @@ cat ../syscall/syscall.csv ../lib/lib.csv | sort >tmp.csv

                          - abc-nuttx-elf-ld -r -d -warn-common -T binfmt/libnxflat/gnu-nxflat.ld -no-check-sections -o $@ hello.o hello-thunk.o + abc-nuttx-elf-ld -r -d -warn-common -T binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections -o $@ hello.o hello-thunk.o @@ -507,7 +510,7 @@ cat ../syscall/syscall.csv ../lib/lib.csv | sort >tmp.csv In this case, it will link together the module's object files (only hello.o here) along with the assembled thunk file, hello-thunk.o to create the second relocatable object, hello.r2. - The linker script, gnu-nxflat.ld is required at this point to correctly position the sections. + The linker script, gnu-nxflat-gotoff.ld is required at this point to correctly position the sections. This linker script produces two segments: An I-Space (Instruction Space) segment containing mostly .text and a D-Space (Data Space) segment containing .got, .data, and .bss sections. @@ -518,6 +521,22 @@ cat ../syscall/syscall.csv ../lib/lib.csv | sort >tmp.csv The option -no-check-sections is required to prevent the linker from failing because these segments overlap.

                          +

                          NOTE: + There are two linker scripts located at binfmt/libnxflat/gnu-nxflat-gotoff.ld. +

                          +
                            +
                          1. + binfmt/libnxflat/gnu-nxflat-gotoff.ld. + Older versions of GCC (at least up to GCC 4.3.3), use GOT-relative addressing to access RO data. + In that case, read-only data (.rodata) must reside in D-Space and this linker script should be used. +
                          2. +
                          3. + binfmt/libnxflat/gnu-nxflat-pcrel.ld. + Newer versions of GCC (at least as of GCC 4.6.3), use PC-relative addressing to access RO data. + In that case, read-only data (.rodata) must reside in I-Space and this linker script should be used. +
                          4. +
                          +

                          Target 4. Finally, this target will use the hello.r2 relocatable object to create the final, NXFLAT module hello by executing ldnxflat. diff --git a/nuttx/TODO b/nuttx/TODO index 72a94290b..30015ef50 100644 --- a/nuttx/TODO +++ b/nuttx/TODO @@ -376,15 +376,15 @@ o Binary loaders (binfmt/) Description: Windows build issue. Some of the configurations that use NXFLAT have the linker script specified like this: - NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections + NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections That will not work for windows-based tools because they require Windows style paths. The solution is to do something like this: if ($(WINTOOL)y) - NXFLATLDSCRIPT=${cygpath -w $(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld} + NXFLATLDSCRIPT=${cygpath -w $(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld} else - NXFLATLDSCRIPT=$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld + NXFLATLDSCRIPT=$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld endif Then use diff --git a/nuttx/binfmt/libnxflat/gnu-nxflat-gotoff.ld b/nuttx/binfmt/libnxflat/gnu-nxflat-gotoff.ld new file mode 100644 index 000000000..c0487212a --- /dev/null +++ b/nuttx/binfmt/libnxflat/gnu-nxflat-gotoff.ld @@ -0,0 +1,182 @@ +/**************************************************************************** + * examples/nxflat/gnu-nxflat-gotoff.ld + * + * Copyright (C) 2009, 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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. + * + ****************************************************************************/ + +MEMORY +{ + ISPACE : ORIGIN = 0x0, LENGTH = 2097152 + DSPACE : ORIGIN = 0x0, LENGTH = 2097152 +} + +/**************************************************************************** + * The XFLAT program image is divided into two segments: + * + * (1) ISpace (Instruction Space). This is the segment that contains + * code (.text). Everything in the segment should be fetch-able + * machine PC instructions (jump, branch, call, etc.). + * (2) DSpace (Data Space). This is the segment that contains both + * read-write data (.data, .bss) as well as read-only data (.rodata). + * Everything in this segment should be access-able with machine + * PIC load and store instructions. + * + * Older versions of GCC (at least up to GCC 4.3.3), use GOT-relative + * addressing to access RO data. In that case, read-only data (.rodata) must + * reside in D-Space and this linker script should be used. + * + * Newer versions of GCC (at least as of GCC 4.6.3), use PC-relative + * addressing to access RO data. In that case, read-only data (.rodata) must + * reside in I-Space and this linker script should NOT be used with those + * newer tools. + * + ****************************************************************************/ + +SECTIONS +{ + .text 0x00000000 : + { + /* ISpace is located at address 0. Every (unrelocated) ISpace + * address is an offset from the begining of this segment. + */ + + text_start = . ; + + *(.text) + *(.text.*) + *(.gnu.warning) + *(.stub) + *(.glue_7) + *(.glue_7t) + *(.jcr) + + /* C++ support: The .init and .fini sections contain XFLAT- + * specific logic to manage static constructors and destructors. + */ + + *(.gnu.linkonce.t.*) + *(.init) + *(.fini) + + /* This is special code area at the end of the normal + text section. It contains a small lookup table at + the start followed by the code pointed to by entries + in the lookup table. */ + + . = ALIGN (4) ; + PROVIDE(__ctbp = .); + *(.call_table_data) + *(.call_table_text) + + _etext = . ; + + } > ISPACE + + /* DSpace is also located at address 0. Every (unrelocated) DSpace + * address is an offset from the begining of this segment. + */ + + .data 0x00000000 : + { + __data_start = . ; + *(.rodata) + *(.rodata1) + *(.rodata.*) + *(.gnu.linkonce.r*) + *(.data) + *(.data1) + *(.data.*) + *(.gnu.linkonce.d*) + *(.data1) + *(.eh_frame) + *(.gcc_except_table) + + *(.gnu.linkonce.s.*) + *(__libc_atexit) + *(__libc_subinit) + *(__libc_subfreeres) + *(.note.ABI-tag) + + /* C++ support. For each global and static local C++ object, + * GCC creates a small subroutine to construct the object. Pointers + * to these routines (not the routines themselves) are stored as + * simple, linear arrays in the .ctors section of the object file. + * Similarly, pointers to global/static destructor routines are + * stored in .dtors. + */ + + *(.gnu.linkonce.d.*) + + _ctors_start = . ; + *(.ctors) + _ctors_end = . ; + _dtors_start = . ; + *(.dtors) + _dtors_end = . ; + + _edata = . ; + edata = ALIGN( 0x10 ) ; + } > DSPACE + + .bss : + { + __bss_start = _edata ; + *(.dynsbss) + *(.sbss) + *(.sbss.*) + *(.scommon) + *(.dynbss) + *(.bss) + *(.bss.*) + *(.bss*) + *(.gnu.linkonce.b*) + *(COMMON) + end = ALIGN( 0x10 ) ; + _end = ALIGN( 0x10 ) ; + } > DSPACE + + .got 0 : { *(.got.plt) *(.got) } + .junk 0 : { *(.rel*) *(.rela*) } + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/nuttx/binfmt/libnxflat/gnu-nxflat-pcrel.ld b/nuttx/binfmt/libnxflat/gnu-nxflat-pcrel.ld new file mode 100644 index 000000000..eb79023d0 --- /dev/null +++ b/nuttx/binfmt/libnxflat/gnu-nxflat-pcrel.ld @@ -0,0 +1,182 @@ +/**************************************************************************** + * examples/nxflat/gnu-nxflat-pcrel.ld + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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. + * + ****************************************************************************/ + +MEMORY +{ + ISPACE : ORIGIN = 0x0, LENGTH = 2097152 + DSPACE : ORIGIN = 0x0, LENGTH = 2097152 +} + +/**************************************************************************** + * The XFLAT program image is divided into two segments: + * + * (1) ISpace (Instruction Space). This is the segment that contains + * code (.text) as well as read-only data (.rodata). Everything in the + * segment should be fetch-able machine PC instructions (jump, branch, + * call, etc.) or PC-relative loads. + * (2) DSpace (Data Space). This is the segment that contains read-write + * data (.data, .bss). Everything in this segment should be access-able + * with machine PIC load and store instructions. + * + * Older versions of GCC (at least up to GCC 4.3.3), use GOT-relative + * addressing to access RO data. In that case, read-only data (.rodata) must + * reside in D-Space and this linker script should NOT be used with those + * older tools. + * + * Newer versions of GCC (at least as of GCC 4.6.3), use PC-relative + * addressing to access RO data. In that case, read-only data (.rodata) must + * reside in I-Space and this linker script should be used. + * + ****************************************************************************/ + +SECTIONS +{ + .text 0x00000000 : + { + /* ISpace is located at address 0. Every (unrelocated) ISpace + * address is an offset from the begining of this segment. + */ + + text_start = . ; + + *(.text) + *(.text.*) + *(.gnu.warning) + *(.stub) + *(.glue_7) + *(.glue_7t) + *(.jcr) + + /* C++ support: The .init and .fini sections contain XFLAT- + * specific logic to manage static constructors and destructors. + */ + + *(.gnu.linkonce.t.*) + *(.init) + *(.fini) + + /* This is special code area at the end of the normal + text section. It contains a small lookup table at + the start followed by the code pointed to by entries + in the lookup table. */ + + . = ALIGN (4) ; + PROVIDE(__ctbp = .); + *(.call_table_data) + *(.call_table_text) + + _etext = . ; + + } > ISPACE + + /* DSpace is also located at address 0. Every (unrelocated) DSpace + * address is an offset from the begining of this segment. + */ + + .data 0x00000000 : + { + __data_start = . ; + *(.rodata) + *(.rodata1) + *(.rodata.*) + *(.gnu.linkonce.r*) + *(.data) + *(.data1) + *(.data.*) + *(.gnu.linkonce.d*) + *(.data1) + *(.eh_frame) + *(.gcc_except_table) + + *(.gnu.linkonce.s.*) + *(__libc_atexit) + *(__libc_subinit) + *(__libc_subfreeres) + *(.note.ABI-tag) + + /* C++ support. For each global and static local C++ object, + * GCC creates a small subroutine to construct the object. Pointers + * to these routines (not the routines themselves) are stored as + * simple, linear arrays in the .ctors section of the object file. + * Similarly, pointers to global/static destructor routines are + * stored in .dtors. + */ + + *(.gnu.linkonce.d.*) + + _ctors_start = . ; + *(.ctors) + _ctors_end = . ; + _dtors_start = . ; + *(.dtors) + _dtors_end = . ; + + _edata = . ; + edata = ALIGN( 0x10 ) ; + } > DSPACE + + .bss : + { + __bss_start = _edata ; + *(.dynsbss) + *(.sbss) + *(.sbss.*) + *(.scommon) + *(.dynbss) + *(.bss) + *(.bss.*) + *(.bss*) + *(.gnu.linkonce.b*) + *(COMMON) + end = ALIGN( 0x10 ) ; + _end = ALIGN( 0x10 ) ; + } > DSPACE + + .got 0 : { *(.got.plt) *(.got) } + .junk 0 : { *(.rel*) *(.rela*) } + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/nuttx/binfmt/libnxflat/gnu-nxflat.ld b/nuttx/binfmt/libnxflat/gnu-nxflat.ld deleted file mode 100644 index e66b1dff5..000000000 --- a/nuttx/binfmt/libnxflat/gnu-nxflat.ld +++ /dev/null @@ -1,172 +0,0 @@ -/**************************************************************************** - * examples/nxflat/nxflat.ld - * - * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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. - * - ****************************************************************************/ - -MEMORY -{ - ISPACE : ORIGIN = 0x0, LENGTH = 2097152 - DSPACE : ORIGIN = 0x0, LENGTH = 2097152 -} - -/**************************************************************************** - * The XFLAT program image is divided into two segments: - * - * (1) ISpace (Instruction Space). This is the segment that contains - * code (.text). Everything in the segment should be fetch-able - * machine PC instructions (jump, branch, call, etc.). - * (2) DSpace (Data Space). This is the segment that contains both - * read-write data (.data, .bss) as well as read-only data (.rodata). - * Everything in this segment should be access-able with machine - * with machine load and store instructions. - ****************************************************************************/ - -SECTIONS -{ - .text 0x00000000 : - { - /* ISpace is located at address 0. Every (unrelocated) ISpace - * address is an offset from the begining of this segment. - */ - - text_start = . ; - - *(.text) - *(.text.*) - *(.gnu.warning) - *(.stub) - *(.glue_7) - *(.glue_7t) - *(.jcr) - - /* C++ support: The .init and .fini sections contain XFLAT- - * specific logic to manage static constructors and destructors. - */ - - *(.gnu.linkonce.t.*) - *(.init) - *(.fini) - - /* This is special code area at the end of the normal - text section. It contains a small lookup table at - the start followed by the code pointed to by entries - in the lookup table. */ - - . = ALIGN (4) ; - PROVIDE(__ctbp = .); - *(.call_table_data) - *(.call_table_text) - - _etext = . ; - - } > ISPACE - - /* DSpace is also located at address 0. Every (unrelocated) DSpace - * address is an offset from the begining of this segment. - */ - - .data 0x00000000 : - { - __data_start = . ; - *(.rodata) - *(.rodata1) - *(.rodata.*) - *(.gnu.linkonce.r*) - *(.data) - *(.data1) - *(.data.*) - *(.gnu.linkonce.d*) - *(.data1) - *(.eh_frame) - *(.gcc_except_table) - - *(.gnu.linkonce.s.*) - *(__libc_atexit) - *(__libc_subinit) - *(__libc_subfreeres) - *(.note.ABI-tag) - - /* C++ support. For each global and static local C++ object, - * GCC creates a small subroutine to construct the object. Pointers - * to these routines (not the routines themselves) are stored as - * simple, linear arrays in the .ctors section of the object file. - * Similarly, pointers to global/static destructor routines are - * stored in .dtors. - */ - - *(.gnu.linkonce.d.*) - - _ctors_start = . ; - *(.ctors) - _ctors_end = . ; - _dtors_start = . ; - *(.dtors) - _dtors_end = . ; - - _edata = . ; - edata = ALIGN( 0x10 ) ; - } > DSPACE - - .bss : - { - __bss_start = _edata ; - *(.dynsbss) - *(.sbss) - *(.sbss.*) - *(.scommon) - *(.dynbss) - *(.bss) - *(.bss.*) - *(.bss*) - *(.gnu.linkonce.b*) - *(COMMON) - end = ALIGN( 0x10 ) ; - _end = ALIGN( 0x10 ) ; - } > DSPACE - - .got 0 : { *(.got.plt) *(.got) } - .junk 0 : { *(.rel*) *(.rela*) } - /* Stabs debugging sections. */ - .stab 0 : { *(.stab) } - .stabstr 0 : { *(.stabstr) } - .stab.excl 0 : { *(.stab.excl) } - .stab.exclstr 0 : { *(.stab.exclstr) } - .stab.index 0 : { *(.stab.index) } - .stab.indexstr 0 : { *(.stab.indexstr) } - .comment 0 : { *(.comment) } - .debug_abbrev 0 : { *(.debug_abbrev) } - .debug_info 0 : { *(.debug_info) } - .debug_line 0 : { *(.debug_line) } - .debug_pubnames 0 : { *(.debug_pubnames) } - .debug_aranges 0 : { *(.debug_aranges) } -} diff --git a/nuttx/configs/amber/hello/Make.defs b/nuttx/configs/amber/hello/Make.defs index 66f3ff799..1c2d8b89e 100644 --- a/nuttx/configs/amber/hello/Make.defs +++ b/nuttx/configs/amber/hello/Make.defs @@ -107,7 +107,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/c5471evm/httpd/Make.defs b/nuttx/configs/c5471evm/httpd/Make.defs index ffc267530..4d94d8342 100644 --- a/nuttx/configs/c5471evm/httpd/Make.defs +++ b/nuttx/configs/c5471evm/httpd/Make.defs @@ -74,7 +74,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld \ + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld \ -no-check-sections LDNXFLATFLAGS = -e main -s 2048 diff --git a/nuttx/configs/c5471evm/nettest/Make.defs b/nuttx/configs/c5471evm/nettest/Make.defs index e784c1119..1f8b7afa1 100644 --- a/nuttx/configs/c5471evm/nettest/Make.defs +++ b/nuttx/configs/c5471evm/nettest/Make.defs @@ -74,7 +74,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld \ + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld \ -no-check-sections LDNXFLATFLAGS = -e main -s 2048 diff --git a/nuttx/configs/c5471evm/nsh/Make.defs b/nuttx/configs/c5471evm/nsh/Make.defs index d9e569158..68a15703e 100644 --- a/nuttx/configs/c5471evm/nsh/Make.defs +++ b/nuttx/configs/c5471evm/nsh/Make.defs @@ -74,7 +74,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld \ + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld \ -no-check-sections LDNXFLATFLAGS = -e main -s 2048 diff --git a/nuttx/configs/c5471evm/ostest/Make.defs b/nuttx/configs/c5471evm/ostest/Make.defs index 9cbfc1d1d..8a0f8c812 100644 --- a/nuttx/configs/c5471evm/ostest/Make.defs +++ b/nuttx/configs/c5471evm/ostest/Make.defs @@ -74,7 +74,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld \ + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld \ -no-check-sections LDNXFLATFLAGS = -e main -s 2048 diff --git a/nuttx/configs/compal_e88/nsh_highram/Make.defs b/nuttx/configs/compal_e88/nsh_highram/Make.defs index e99d5635d..c5890828f 100644 --- a/nuttx/configs/compal_e88/nsh_highram/Make.defs +++ b/nuttx/configs/compal_e88/nsh_highram/Make.defs @@ -83,7 +83,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld \ + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld \ -no-check-sections LDNXFLATFLAGS = -e main -s 2048 diff --git a/nuttx/configs/compal_e99/nsh_compalram/Make.defs b/nuttx/configs/compal_e99/nsh_compalram/Make.defs index 4759fc76a..16e38b666 100644 --- a/nuttx/configs/compal_e99/nsh_compalram/Make.defs +++ b/nuttx/configs/compal_e99/nsh_compalram/Make.defs @@ -83,7 +83,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld \ + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld \ -no-check-sections LDNXFLATFLAGS = -e main -s 2048 diff --git a/nuttx/configs/compal_e99/nsh_highram/Make.defs b/nuttx/configs/compal_e99/nsh_highram/Make.defs index e99d5635d..c5890828f 100644 --- a/nuttx/configs/compal_e99/nsh_highram/Make.defs +++ b/nuttx/configs/compal_e99/nsh_highram/Make.defs @@ -83,7 +83,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld \ + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld \ -no-check-sections LDNXFLATFLAGS = -e main -s 2048 diff --git a/nuttx/configs/demo9s12ne64/ostest/Make.defs b/nuttx/configs/demo9s12ne64/ostest/Make.defs index 727ebb561..9edf5adf9 100644 --- a/nuttx/configs/demo9s12ne64/ostest/Make.defs +++ b/nuttx/configs/demo9s12ne64/ostest/Make.defs @@ -105,7 +105,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/ea3131/nsh/Make.defs b/nuttx/configs/ea3131/nsh/Make.defs index cd49f56af..28e881ccb 100644 --- a/nuttx/configs/ea3131/nsh/Make.defs +++ b/nuttx/configs/ea3131/nsh/Make.defs @@ -115,7 +115,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/ea3131/ostest/Make.defs b/nuttx/configs/ea3131/ostest/Make.defs index f07f4d452..ed7eb9290 100644 --- a/nuttx/configs/ea3131/ostest/Make.defs +++ b/nuttx/configs/ea3131/ostest/Make.defs @@ -115,7 +115,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/ea3131/pgnsh/Make.defs b/nuttx/configs/ea3131/pgnsh/Make.defs index 1097a8d72..7b09759ea 100644 --- a/nuttx/configs/ea3131/pgnsh/Make.defs +++ b/nuttx/configs/ea3131/pgnsh/Make.defs @@ -115,7 +115,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/ea3131/usbserial/Make.defs b/nuttx/configs/ea3131/usbserial/Make.defs index 3fe5f8f93..614221fb3 100644 --- a/nuttx/configs/ea3131/usbserial/Make.defs +++ b/nuttx/configs/ea3131/usbserial/Make.defs @@ -115,7 +115,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/ea3131/usbstorage/Make.defs b/nuttx/configs/ea3131/usbstorage/Make.defs index de351b256..4aa007069 100644 --- a/nuttx/configs/ea3131/usbstorage/Make.defs +++ b/nuttx/configs/ea3131/usbstorage/Make.defs @@ -115,7 +115,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/ea3152/ostest/Make.defs b/nuttx/configs/ea3152/ostest/Make.defs index 9bb350e36..8ca8f6e6a 100644 --- a/nuttx/configs/ea3152/ostest/Make.defs +++ b/nuttx/configs/ea3152/ostest/Make.defs @@ -115,7 +115,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/eagle100/README.txt b/nuttx/configs/eagle100/README.txt index 105bd5ff1..b4bca39cb 100644 --- a/nuttx/configs/eagle100/README.txt +++ b/nuttx/configs/eagle100/README.txt @@ -157,12 +157,14 @@ NuttX OABI "buildroot" Toolchain configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI configuration such as cortexm3-defconfig-4.3.3 - 2. Modify the Make.defs file to use the OABI converntions: + 2. Modify the Make.defs file to use the OABI conventions: +CROSSDEV = arm-nuttx-elf- +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections -CROSSDEV = arm-nuttx-eabi- -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections NXFLAT Toolchain ^^^^^^^^^^^^^^^^ diff --git a/nuttx/configs/eagle100/httpd/Make.defs b/nuttx/configs/eagle100/httpd/Make.defs index 8d3cc9c25..dc252dfb3 100644 --- a/nuttx/configs/eagle100/httpd/Make.defs +++ b/nuttx/configs/eagle100/httpd/Make.defs @@ -98,7 +98,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld \ + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld \ -no-check-sections LDNXFLATFLAGS = -e main -s 2048 diff --git a/nuttx/configs/eagle100/nettest/Make.defs b/nuttx/configs/eagle100/nettest/Make.defs index ca5049282..3de14846e 100644 --- a/nuttx/configs/eagle100/nettest/Make.defs +++ b/nuttx/configs/eagle100/nettest/Make.defs @@ -98,7 +98,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld \ + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld \ -no-check-sections LDNXFLATFLAGS = -e main -s 2048 diff --git a/nuttx/configs/eagle100/nsh/Make.defs b/nuttx/configs/eagle100/nsh/Make.defs index 499299495..ff6675933 100644 --- a/nuttx/configs/eagle100/nsh/Make.defs +++ b/nuttx/configs/eagle100/nsh/Make.defs @@ -98,7 +98,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld \ + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld \ -no-check-sections LDNXFLATFLAGS = -e main -s 2048 diff --git a/nuttx/configs/eagle100/nxflat/Make.defs b/nuttx/configs/eagle100/nxflat/Make.defs index d735c3942..41e738ec8 100644 --- a/nuttx/configs/eagle100/nxflat/Make.defs +++ b/nuttx/configs/eagle100/nxflat/Make.defs @@ -101,7 +101,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld \ + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld \ -no-check-sections LDNXFLATFLAGS = -e main -s 2048 diff --git a/nuttx/configs/eagle100/ostest/Make.defs b/nuttx/configs/eagle100/ostest/Make.defs index 641fcbaba..78db5644e 100644 --- a/nuttx/configs/eagle100/ostest/Make.defs +++ b/nuttx/configs/eagle100/ostest/Make.defs @@ -98,7 +98,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld \ + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld \ -no-check-sections LDNXFLATFLAGS = -e main -s 2048 diff --git a/nuttx/configs/eagle100/thttpd/Make.defs b/nuttx/configs/eagle100/thttpd/Make.defs index 999db3a59..92f68d9f1 100644 --- a/nuttx/configs/eagle100/thttpd/Make.defs +++ b/nuttx/configs/eagle100/thttpd/Make.defs @@ -101,7 +101,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld \ + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld \ -no-check-sections LDNXFLATFLAGS = -e main -s 2048 diff --git a/nuttx/configs/ekk-lm3s9b96/README.txt b/nuttx/configs/ekk-lm3s9b96/README.txt index 16568dbda..2ad435477 100644 --- a/nuttx/configs/ekk-lm3s9b96/README.txt +++ b/nuttx/configs/ekk-lm3s9b96/README.txt @@ -235,12 +235,14 @@ NuttX OABI "buildroot" Toolchain configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI configuration such as cortexm3-defconfig-4.3.3 - 2. Modify the Make.defs file to use the OABI converntions: + 2. Modify the Make.defs file to use the OABI conventions: +CROSSDEV = arm-nuttx-elf- +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections -CROSSDEV = arm-nuttx-eabi- -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections NXFLAT Toolchain ^^^^^^^^^^^^^^^^ diff --git a/nuttx/configs/ekk-lm3s9b96/nsh/Make.defs b/nuttx/configs/ekk-lm3s9b96/nsh/Make.defs index e810ec175..c14dccbb9 100644 --- a/nuttx/configs/ekk-lm3s9b96/nsh/Make.defs +++ b/nuttx/configs/ekk-lm3s9b96/nsh/Make.defs @@ -118,7 +118,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/ekk-lm3s9b96/ostest/Make.defs b/nuttx/configs/ekk-lm3s9b96/ostest/Make.defs index ca38be836..4068b73fd 100644 --- a/nuttx/configs/ekk-lm3s9b96/ostest/Make.defs +++ b/nuttx/configs/ekk-lm3s9b96/ostest/Make.defs @@ -118,7 +118,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/fire-stm32v2/README.txt b/nuttx/configs/fire-stm32v2/README.txt index 74f3c7294..9e5d94c23 100644 --- a/nuttx/configs/fire-stm32v2/README.txt +++ b/nuttx/configs/fire-stm32v2/README.txt @@ -357,12 +357,14 @@ NuttX OABI "buildroot" Toolchain configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI configuration such as cortexm3-defconfig-4.3.3 - 2. Modify the Make.defs file to use the OABI converntions: + 2. Modify the Make.defs file to use the OABI conventions: +CROSSDEV = arm-nuttx-elf- +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections -CROSSDEV = arm-nuttx-eabi- -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections NXFLAT Toolchain ================ diff --git a/nuttx/configs/fire-stm32v2/nsh/Make.defs b/nuttx/configs/fire-stm32v2/nsh/Make.defs index f64dda4d2..bd63f7c6b 100644 --- a/nuttx/configs/fire-stm32v2/nsh/Make.defs +++ b/nuttx/configs/fire-stm32v2/nsh/Make.defs @@ -153,7 +153,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/hymini-stm32v/README.txt b/nuttx/configs/hymini-stm32v/README.txt index 03658be0a..51f3c1fe3 100644 --- a/nuttx/configs/hymini-stm32v/README.txt +++ b/nuttx/configs/hymini-stm32v/README.txt @@ -177,12 +177,14 @@ NuttX OABI "buildroot" Toolchain configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI configuration such as cortexm3-defconfig-4.3.3 - 2. Modify the Make.defs file to use the OABI converntions: + 2. Modify the Make.defs file to use the OABI conventions: +CROSSDEV = arm-nuttx-elf- +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections -CROSSDEV = arm-nuttx-eabi- -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections NXFLAT Toolchain ================ diff --git a/nuttx/configs/hymini-stm32v/buttons/Make.defs b/nuttx/configs/hymini-stm32v/buttons/Make.defs index eb121c2cb..efc29cb1d 100644 --- a/nuttx/configs/hymini-stm32v/buttons/Make.defs +++ b/nuttx/configs/hymini-stm32v/buttons/Make.defs @@ -129,7 +129,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/hymini-stm32v/nsh/Make.defs b/nuttx/configs/hymini-stm32v/nsh/Make.defs index a0809f98a..cade80762 100644 --- a/nuttx/configs/hymini-stm32v/nsh/Make.defs +++ b/nuttx/configs/hymini-stm32v/nsh/Make.defs @@ -129,7 +129,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/hymini-stm32v/nsh2/Make.defs b/nuttx/configs/hymini-stm32v/nsh2/Make.defs index 72960ee27..269b4979e 100644 --- a/nuttx/configs/hymini-stm32v/nsh2/Make.defs +++ b/nuttx/configs/hymini-stm32v/nsh2/Make.defs @@ -129,7 +129,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/hymini-stm32v/nx/Make.defs b/nuttx/configs/hymini-stm32v/nx/Make.defs index d647c7fcd..fce4ec279 100644 --- a/nuttx/configs/hymini-stm32v/nx/Make.defs +++ b/nuttx/configs/hymini-stm32v/nx/Make.defs @@ -129,7 +129,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/hymini-stm32v/nxlines/Make.defs b/nuttx/configs/hymini-stm32v/nxlines/Make.defs index fa66e6be0..8943c4cb7 100644 --- a/nuttx/configs/hymini-stm32v/nxlines/Make.defs +++ b/nuttx/configs/hymini-stm32v/nxlines/Make.defs @@ -131,7 +131,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/hymini-stm32v/usbserial/Make.defs b/nuttx/configs/hymini-stm32v/usbserial/Make.defs index d0a2a80cc..1e8c90b12 100644 --- a/nuttx/configs/hymini-stm32v/usbserial/Make.defs +++ b/nuttx/configs/hymini-stm32v/usbserial/Make.defs @@ -129,7 +129,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/hymini-stm32v/usbstorage/Make.defs b/nuttx/configs/hymini-stm32v/usbstorage/Make.defs index ee870eab4..8acc8db4a 100644 --- a/nuttx/configs/hymini-stm32v/usbstorage/Make.defs +++ b/nuttx/configs/hymini-stm32v/usbstorage/Make.defs @@ -129,7 +129,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/kwikstik-k40/README.txt b/nuttx/configs/kwikstik-k40/README.txt index a320cbb05..246fa912e 100644 --- a/nuttx/configs/kwikstik-k40/README.txt +++ b/nuttx/configs/kwikstik-k40/README.txt @@ -300,12 +300,14 @@ NuttX OABI "buildroot" Toolchain configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI configuration such as cortexm3-defconfig-4.3.3 - 2. Modify the Make.defs file to use the OABI converntions: + 2. Modify the Make.defs file to use the OABI conventions: +CROSSDEV = arm-nuttx-elf- +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections -CROSSDEV = arm-nuttx-eabi- -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections NXFLAT Toolchain ================ diff --git a/nuttx/configs/kwikstik-k40/ostest/Make.defs b/nuttx/configs/kwikstik-k40/ostest/Make.defs index beba9e397..a51f37e94 100644 --- a/nuttx/configs/kwikstik-k40/ostest/Make.defs +++ b/nuttx/configs/kwikstik-k40/ostest/Make.defs @@ -117,7 +117,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/lincoln60/README.txt b/nuttx/configs/lincoln60/README.txt index abbc57204..35fe32267 100644 --- a/nuttx/configs/lincoln60/README.txt +++ b/nuttx/configs/lincoln60/README.txt @@ -199,12 +199,14 @@ NuttX OABI "buildroot" Toolchain configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI configuration such as cortexm3-defconfig-4.3.3 - 2. Modify the Make.defs file to use the OABI converntions: + 2. Modify the Make.defs file to use the OABI conerntions: +CROSSDEV = arm-nuttx-elf- +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections -CROSSDEV = arm-nuttx-eabi- -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections NXFLAT Toolchain ^^^^^^^^^^^^^^^^ diff --git a/nuttx/configs/lincoln60/nsh/Make.defs b/nuttx/configs/lincoln60/nsh/Make.defs index 7b3c3318a..cf76f97f2 100644 --- a/nuttx/configs/lincoln60/nsh/Make.defs +++ b/nuttx/configs/lincoln60/nsh/Make.defs @@ -117,7 +117,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/lincoln60/ostest/Make.defs b/nuttx/configs/lincoln60/ostest/Make.defs index bd4b25701..044b27dc4 100644 --- a/nuttx/configs/lincoln60/ostest/Make.defs +++ b/nuttx/configs/lincoln60/ostest/Make.defs @@ -117,7 +117,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/lm3s6432-s2e/README.txt b/nuttx/configs/lm3s6432-s2e/README.txt index 10ceda15a..460b5546d 100644 --- a/nuttx/configs/lm3s6432-s2e/README.txt +++ b/nuttx/configs/lm3s6432-s2e/README.txt @@ -229,12 +229,14 @@ NuttX OABI "buildroot" Toolchain configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI configuration such as cortexm3-defconfig-4.3.3 - 2. Modify the Make.defs file to use the OABI converntions: + 2. Modify the Make.defs file to use the OABI conventions: +CROSSDEV = arm-nuttx-elf- +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections -CROSSDEV = arm-nuttx-eabi- -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections NXFLAT Toolchain ^^^^^^^^^^^^^^^^ diff --git a/nuttx/configs/lm3s6432-s2e/nsh/Make.defs b/nuttx/configs/lm3s6432-s2e/nsh/Make.defs index e463a1742..c9ade8028 100644 --- a/nuttx/configs/lm3s6432-s2e/nsh/Make.defs +++ b/nuttx/configs/lm3s6432-s2e/nsh/Make.defs @@ -117,7 +117,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/lm3s6432-s2e/ostest/Make.defs b/nuttx/configs/lm3s6432-s2e/ostest/Make.defs index 33f0d43ed..5f48145bf 100644 --- a/nuttx/configs/lm3s6432-s2e/ostest/Make.defs +++ b/nuttx/configs/lm3s6432-s2e/ostest/Make.defs @@ -117,7 +117,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/lm3s6965-ek/README.txt b/nuttx/configs/lm3s6965-ek/README.txt index fc70b75fc..4aba09bee 100644 --- a/nuttx/configs/lm3s6965-ek/README.txt +++ b/nuttx/configs/lm3s6965-ek/README.txt @@ -261,12 +261,14 @@ NuttX OABI "buildroot" Toolchain configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI configuration such as cortexm3-defconfig-4.3.3 - 2. Modify the Make.defs file to use the OABI converntions: + 2. Modify the Make.defs file to use the OABI conventions: +CROSSDEV = arm-nuttx-elf- +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections -CROSSDEV = arm-nuttx-eabi- -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections NXFLAT Toolchain ^^^^^^^^^^^^^^^^ diff --git a/nuttx/configs/lm3s6965-ek/nsh/Make.defs b/nuttx/configs/lm3s6965-ek/nsh/Make.defs index 5aaed9009..6fc8616aa 100644 --- a/nuttx/configs/lm3s6965-ek/nsh/Make.defs +++ b/nuttx/configs/lm3s6965-ek/nsh/Make.defs @@ -117,7 +117,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/lm3s6965-ek/nx/Make.defs b/nuttx/configs/lm3s6965-ek/nx/Make.defs index 8b99d7de7..887bb823a 100644 --- a/nuttx/configs/lm3s6965-ek/nx/Make.defs +++ b/nuttx/configs/lm3s6965-ek/nx/Make.defs @@ -117,7 +117,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/lm3s6965-ek/ostest/Make.defs b/nuttx/configs/lm3s6965-ek/ostest/Make.defs index 434b21e24..0c02e22bb 100644 --- a/nuttx/configs/lm3s6965-ek/ostest/Make.defs +++ b/nuttx/configs/lm3s6965-ek/ostest/Make.defs @@ -117,7 +117,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/lm3s8962-ek/README.txt b/nuttx/configs/lm3s8962-ek/README.txt index 043e5ceb3..570d158a2 100644 --- a/nuttx/configs/lm3s8962-ek/README.txt +++ b/nuttx/configs/lm3s8962-ek/README.txt @@ -245,12 +245,14 @@ NuttX OABI "buildroot" Toolchain configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI configuration such as cortexm3-defconfig-4.3.3 - 2. Modify the Make.defs file to use the OABI converntions: + 2. Modify the Make.defs file to use the OABI conventions: +CROSSDEV = arm-nuttx-elf- +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections -CROSSDEV = arm-nuttx-eabi- -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections NXFLAT Toolchain ^^^^^^^^^^^^^^^^ diff --git a/nuttx/configs/lm3s8962-ek/nsh/Make.defs b/nuttx/configs/lm3s8962-ek/nsh/Make.defs index d7be642cd..671ccec32 100644 --- a/nuttx/configs/lm3s8962-ek/nsh/Make.defs +++ b/nuttx/configs/lm3s8962-ek/nsh/Make.defs @@ -117,7 +117,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/lm3s8962-ek/nx/Make.defs b/nuttx/configs/lm3s8962-ek/nx/Make.defs index bf07df29a..2563c58dd 100644 --- a/nuttx/configs/lm3s8962-ek/nx/Make.defs +++ b/nuttx/configs/lm3s8962-ek/nx/Make.defs @@ -117,7 +117,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/lm3s8962-ek/ostest/Make.defs b/nuttx/configs/lm3s8962-ek/ostest/Make.defs index 94389216c..2559ed89a 100644 --- a/nuttx/configs/lm3s8962-ek/ostest/Make.defs +++ b/nuttx/configs/lm3s8962-ek/ostest/Make.defs @@ -117,7 +117,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/lpc4330-xplorer/README.txt b/nuttx/configs/lpc4330-xplorer/README.txt index a613edada..ea1098be5 100644 --- a/nuttx/configs/lpc4330-xplorer/README.txt +++ b/nuttx/configs/lpc4330-xplorer/README.txt @@ -511,12 +511,14 @@ NuttX OABI "buildroot" Toolchain configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI configuration such as cortexm3-defconfig-4.3.3 - 2. Modify the Make.defs file to use the OABI converntions: + 2. Modify the Make.defs file to use the OABI conventions: +CROSSDEV = arm-nuttx-elf- +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections -CROSSDEV = arm-nuttx-eabi- -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections NXFLAT Toolchain ================ diff --git a/nuttx/configs/lpc4330-xplorer/nsh/Make.defs b/nuttx/configs/lpc4330-xplorer/nsh/Make.defs index 757759ecc..51439ac22 100644 --- a/nuttx/configs/lpc4330-xplorer/nsh/Make.defs +++ b/nuttx/configs/lpc4330-xplorer/nsh/Make.defs @@ -174,7 +174,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/lpc4330-xplorer/ostest/Make.defs b/nuttx/configs/lpc4330-xplorer/ostest/Make.defs index 757759ecc..51439ac22 100644 --- a/nuttx/configs/lpc4330-xplorer/ostest/Make.defs +++ b/nuttx/configs/lpc4330-xplorer/ostest/Make.defs @@ -174,7 +174,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/lpcxpresso-lpc1768/README.txt b/nuttx/configs/lpcxpresso-lpc1768/README.txt index 65f58d552..cbc5f50e8 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/README.txt +++ b/nuttx/configs/lpcxpresso-lpc1768/README.txt @@ -455,12 +455,14 @@ NuttX OABI "buildroot" Toolchain configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI configuration such as cortexm3-defconfig-4.3.3 - 2. Modify the Make.defs file to use the OABI converntions: + 2. Modify the Make.defs file to use the OABI conventions: +CROSSDEV = arm-nuttx-elf- +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections -CROSSDEV = arm-nuttx-eabi- -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections NXFLAT Toolchain ^^^^^^^^^^^^^^^^ diff --git a/nuttx/configs/lpcxpresso-lpc1768/dhcpd/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/dhcpd/Make.defs index 15109a1ad..55da02a15 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/dhcpd/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/dhcpd/Make.defs @@ -129,7 +129,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/lpcxpresso-lpc1768/nsh/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/nsh/Make.defs index b29d10982..52831a279 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/nsh/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/nsh/Make.defs @@ -129,7 +129,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/lpcxpresso-lpc1768/nx/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/nx/Make.defs index 31286436a..59aeb5187 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/nx/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/nx/Make.defs @@ -129,7 +129,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/lpcxpresso-lpc1768/ostest/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/ostest/Make.defs index 975cdf460..6d228a936 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/ostest/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/ostest/Make.defs @@ -129,7 +129,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/lpcxpresso-lpc1768/thttpd/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/thttpd/Make.defs index 67534a5c1..b6a324546 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/thttpd/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/thttpd/Make.defs @@ -88,14 +88,14 @@ ifeq ($(WINTOOL),y) ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}" ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/thttpd/ld.script}" MAXOPTIMIZATION = -O2 - NXFLATLDSCRIPT = -T "${shell cygpath -w $(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld}" + NXFLATLDSCRIPT = -T "${shell cygpath -w $(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld}" else # Linux/Cygwin-native toolchain MKDEP = $(TOPDIR)/tools/mkdeps.sh ARCHINCLUDES = -I. -isystem $(TOPDIR)/include ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/thttpd/ld.script - NXFLATLDSCRIPT = -T"$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld" + NXFLATLDSCRIPT = -T"$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld" endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/lpcxpresso-lpc1768/usbstorage/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/usbstorage/Make.defs index 087a92287..793dfcdf1 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/usbstorage/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/usbstorage/Make.defs @@ -129,7 +129,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/mbed/README.txt b/nuttx/configs/mbed/README.txt index 601c9a0b2..df509a199 100644 --- a/nuttx/configs/mbed/README.txt +++ b/nuttx/configs/mbed/README.txt @@ -169,12 +169,14 @@ NuttX OABI "buildroot" Toolchain configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI configuration such as cortexm3-defconfig-4.3.3 - 2. Modify the Make.defs file to use the OABI converntions: + 2. Modify the Make.defs file to use the OABI conventions: +CROSSDEV = arm-nuttx-elf- +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections -CROSSDEV = arm-nuttx-eabi- -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections NXFLAT Toolchain ^^^^^^^^^^^^^^^^ diff --git a/nuttx/configs/mbed/hidkbd/Make.defs b/nuttx/configs/mbed/hidkbd/Make.defs index 043340da1..b1dfb73e1 100644 --- a/nuttx/configs/mbed/hidkbd/Make.defs +++ b/nuttx/configs/mbed/hidkbd/Make.defs @@ -117,7 +117,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/mbed/nsh/Make.defs b/nuttx/configs/mbed/nsh/Make.defs index 549178e9c..f1983a7b7 100644 --- a/nuttx/configs/mbed/nsh/Make.defs +++ b/nuttx/configs/mbed/nsh/Make.defs @@ -117,7 +117,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/mcu123-lpc214x/composite/Make.defs b/nuttx/configs/mcu123-lpc214x/composite/Make.defs index f2f0ee8e8..fcbc0b809 100644 --- a/nuttx/configs/mcu123-lpc214x/composite/Make.defs +++ b/nuttx/configs/mcu123-lpc214x/composite/Make.defs @@ -110,7 +110,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld \ + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld \ -no-check-sections LDNXFLATFLAGS = -e main -s 2048 diff --git a/nuttx/configs/mcu123-lpc214x/nsh/Make.defs b/nuttx/configs/mcu123-lpc214x/nsh/Make.defs index de09916e5..eed15974a 100644 --- a/nuttx/configs/mcu123-lpc214x/nsh/Make.defs +++ b/nuttx/configs/mcu123-lpc214x/nsh/Make.defs @@ -110,7 +110,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld \ + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld \ -no-check-sections LDNXFLATFLAGS = -e main -s 2048 diff --git a/nuttx/configs/mcu123-lpc214x/ostest/Make.defs b/nuttx/configs/mcu123-lpc214x/ostest/Make.defs index bc72ca9bd..46beab526 100644 --- a/nuttx/configs/mcu123-lpc214x/ostest/Make.defs +++ b/nuttx/configs/mcu123-lpc214x/ostest/Make.defs @@ -110,7 +110,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld \ + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld \ -no-check-sections LDNXFLATFLAGS = -e main -s 2048 diff --git a/nuttx/configs/mcu123-lpc214x/usbserial/Make.defs b/nuttx/configs/mcu123-lpc214x/usbserial/Make.defs index 106224ef1..377c39b1d 100644 --- a/nuttx/configs/mcu123-lpc214x/usbserial/Make.defs +++ b/nuttx/configs/mcu123-lpc214x/usbserial/Make.defs @@ -110,7 +110,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld \ + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld \ -no-check-sections LDNXFLATFLAGS = -e main -s 2048 diff --git a/nuttx/configs/mcu123-lpc214x/usbstorage/Make.defs b/nuttx/configs/mcu123-lpc214x/usbstorage/Make.defs index bf1b9cab4..d26a22d6f 100644 --- a/nuttx/configs/mcu123-lpc214x/usbstorage/Make.defs +++ b/nuttx/configs/mcu123-lpc214x/usbstorage/Make.defs @@ -110,7 +110,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld \ + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld \ -no-check-sections LDNXFLATFLAGS = -e main -s 2048 diff --git a/nuttx/configs/micropendous3/hello/Make.defs b/nuttx/configs/micropendous3/hello/Make.defs index 178f35556..bd48d79c9 100644 --- a/nuttx/configs/micropendous3/hello/Make.defs +++ b/nuttx/configs/micropendous3/hello/Make.defs @@ -107,7 +107,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/mirtoo/nsh/Make.defs b/nuttx/configs/mirtoo/nsh/Make.defs index 17b7cad21..de0a190f6 100644 --- a/nuttx/configs/mirtoo/nsh/Make.defs +++ b/nuttx/configs/mirtoo/nsh/Make.defs @@ -154,7 +154,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/mirtoo/nxffs/Make.defs b/nuttx/configs/mirtoo/nxffs/Make.defs index 908536b66..a6992ee53 100644 --- a/nuttx/configs/mirtoo/nxffs/Make.defs +++ b/nuttx/configs/mirtoo/nxffs/Make.defs @@ -154,7 +154,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/mirtoo/ostest/Make.defs b/nuttx/configs/mirtoo/ostest/Make.defs index 7c200ea47..71bd9d5ba 100644 --- a/nuttx/configs/mirtoo/ostest/Make.defs +++ b/nuttx/configs/mirtoo/ostest/Make.defs @@ -154,7 +154,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/mx1ads/ostest/Make.defs b/nuttx/configs/mx1ads/ostest/Make.defs index 71e053b0a..9b9c61df8 100644 --- a/nuttx/configs/mx1ads/ostest/Make.defs +++ b/nuttx/configs/mx1ads/ostest/Make.defs @@ -84,7 +84,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld \ + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld \ -no-check-sections LDNXFLATFLAGS = -e main -s 2048 diff --git a/nuttx/configs/ne64badge/ostest/Make.defs b/nuttx/configs/ne64badge/ostest/Make.defs index 9521a0a66..2858d30f1 100644 --- a/nuttx/configs/ne64badge/ostest/Make.defs +++ b/nuttx/configs/ne64badge/ostest/Make.defs @@ -105,7 +105,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/ntosd-dm320/nettest/Make.defs b/nuttx/configs/ntosd-dm320/nettest/Make.defs index 30d369c2a..e28c1a360 100644 --- a/nuttx/configs/ntosd-dm320/nettest/Make.defs +++ b/nuttx/configs/ntosd-dm320/nettest/Make.defs @@ -120,7 +120,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld \ + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld \ -no-check-sections LDNXFLATFLAGS = -e main -s 2048 diff --git a/nuttx/configs/ntosd-dm320/nsh/Make.defs b/nuttx/configs/ntosd-dm320/nsh/Make.defs index 14038f756..aff7f4240 100644 --- a/nuttx/configs/ntosd-dm320/nsh/Make.defs +++ b/nuttx/configs/ntosd-dm320/nsh/Make.defs @@ -120,7 +120,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld \ + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld \ -no-check-sections LDNXFLATFLAGS = -e main -s 2048 diff --git a/nuttx/configs/ntosd-dm320/ostest/Make.defs b/nuttx/configs/ntosd-dm320/ostest/Make.defs index 4618c4246..6766b4915 100644 --- a/nuttx/configs/ntosd-dm320/ostest/Make.defs +++ b/nuttx/configs/ntosd-dm320/ostest/Make.defs @@ -120,7 +120,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld \ + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld \ -no-check-sections LDNXFLATFLAGS = -e main -s 2048 diff --git a/nuttx/configs/ntosd-dm320/poll/Make.defs b/nuttx/configs/ntosd-dm320/poll/Make.defs index c06139bd6..a111fed65 100644 --- a/nuttx/configs/ntosd-dm320/poll/Make.defs +++ b/nuttx/configs/ntosd-dm320/poll/Make.defs @@ -120,7 +120,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld \ + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld \ -no-check-sections LDNXFLATFLAGS = -e main -s 2048 diff --git a/nuttx/configs/ntosd-dm320/thttpd/Make.defs b/nuttx/configs/ntosd-dm320/thttpd/Make.defs index 075f72eaa..a0e501376 100644 --- a/nuttx/configs/ntosd-dm320/thttpd/Make.defs +++ b/nuttx/configs/ntosd-dm320/thttpd/Make.defs @@ -120,7 +120,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld \ + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld \ -no-check-sections LDNXFLATFLAGS = -e main -s 2048 diff --git a/nuttx/configs/ntosd-dm320/udp/Make.defs b/nuttx/configs/ntosd-dm320/udp/Make.defs index 66750f13d..16ed8eceb 100644 --- a/nuttx/configs/ntosd-dm320/udp/Make.defs +++ b/nuttx/configs/ntosd-dm320/udp/Make.defs @@ -120,7 +120,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld \ + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld \ -no-check-sections LDNXFLATFLAGS = -e main -s 2048 diff --git a/nuttx/configs/ntosd-dm320/uip/Make.defs b/nuttx/configs/ntosd-dm320/uip/Make.defs index d59b96e7c..d9425c05e 100644 --- a/nuttx/configs/ntosd-dm320/uip/Make.defs +++ b/nuttx/configs/ntosd-dm320/uip/Make.defs @@ -120,7 +120,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld \ + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld \ -no-check-sections LDNXFLATFLAGS = -e main -s 2048 diff --git a/nuttx/configs/nucleus2g/README.txt b/nuttx/configs/nucleus2g/README.txt index 01b6adef7..39ae370cc 100644 --- a/nuttx/configs/nucleus2g/README.txt +++ b/nuttx/configs/nucleus2g/README.txt @@ -229,12 +229,14 @@ NuttX OABI "buildroot" Toolchain configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI configuration such as cortexm3-defconfig-4.3.3 - 2. Modify the Make.defs file to use the OABI converntions: + 2. Modify the Make.defs file to use the OABI conventions: +CROSSDEV = arm-nuttx-elf- +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections -CROSSDEV = arm-nuttx-eabi- -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections NXFLAT Toolchain ^^^^^^^^^^^^^^^^ diff --git a/nuttx/configs/nucleus2g/nsh/Make.defs b/nuttx/configs/nucleus2g/nsh/Make.defs index e21f7f1c8..85e175df0 100644 --- a/nuttx/configs/nucleus2g/nsh/Make.defs +++ b/nuttx/configs/nucleus2g/nsh/Make.defs @@ -117,7 +117,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/nucleus2g/ostest/Make.defs b/nuttx/configs/nucleus2g/ostest/Make.defs index 5696eae22..fc12eccad 100644 --- a/nuttx/configs/nucleus2g/ostest/Make.defs +++ b/nuttx/configs/nucleus2g/ostest/Make.defs @@ -117,7 +117,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/nucleus2g/usbserial/Make.defs b/nuttx/configs/nucleus2g/usbserial/Make.defs index 2cdccc959..d82b5d1bc 100644 --- a/nuttx/configs/nucleus2g/usbserial/Make.defs +++ b/nuttx/configs/nucleus2g/usbserial/Make.defs @@ -117,7 +117,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/nucleus2g/usbstorage/Make.defs b/nuttx/configs/nucleus2g/usbstorage/Make.defs index 79f1b8c1f..d5819e82a 100644 --- a/nuttx/configs/nucleus2g/usbstorage/Make.defs +++ b/nuttx/configs/nucleus2g/usbstorage/Make.defs @@ -117,7 +117,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/olimex-lpc1766stk/README.txt b/nuttx/configs/olimex-lpc1766stk/README.txt index 96692688c..dcea9d0b7 100644 --- a/nuttx/configs/olimex-lpc1766stk/README.txt +++ b/nuttx/configs/olimex-lpc1766stk/README.txt @@ -317,12 +317,14 @@ NuttX OABI "buildroot" Toolchain configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI configuration such as cortexm3-defconfig-4.3.3 - 2. Modify the Make.defs file to use the OABI converntions: + 2. Modify the Make.defs file to use the OABI conventions: +CROSSDEV = arm-nuttx-elf- +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections -CROSSDEV = arm-nuttx-eabi- -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections NXFLAT Toolchain ^^^^^^^^^^^^^^^^ diff --git a/nuttx/configs/olimex-lpc1766stk/ftpc/Make.defs b/nuttx/configs/olimex-lpc1766stk/ftpc/Make.defs index fb8d55023..352c03174 100644 --- a/nuttx/configs/olimex-lpc1766stk/ftpc/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/ftpc/Make.defs @@ -120,7 +120,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/olimex-lpc1766stk/hidkbd/Make.defs b/nuttx/configs/olimex-lpc1766stk/hidkbd/Make.defs index 1997d66b3..017a79e7d 100644 --- a/nuttx/configs/olimex-lpc1766stk/hidkbd/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/hidkbd/Make.defs @@ -117,7 +117,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/olimex-lpc1766stk/nettest/Make.defs b/nuttx/configs/olimex-lpc1766stk/nettest/Make.defs index 203662941..652899c08 100644 --- a/nuttx/configs/olimex-lpc1766stk/nettest/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/nettest/Make.defs @@ -117,7 +117,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/olimex-lpc1766stk/nsh/Make.defs b/nuttx/configs/olimex-lpc1766stk/nsh/Make.defs index 7110759ba..b517fae43 100644 --- a/nuttx/configs/olimex-lpc1766stk/nsh/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/nsh/Make.defs @@ -117,7 +117,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/olimex-lpc1766stk/nx/Make.defs b/nuttx/configs/olimex-lpc1766stk/nx/Make.defs index e8325f780..2d0d63b19 100644 --- a/nuttx/configs/olimex-lpc1766stk/nx/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/nx/Make.defs @@ -117,7 +117,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/olimex-lpc1766stk/ostest/Make.defs b/nuttx/configs/olimex-lpc1766stk/ostest/Make.defs index f7775e072..6883694a3 100644 --- a/nuttx/configs/olimex-lpc1766stk/ostest/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/ostest/Make.defs @@ -117,7 +117,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/olimex-lpc1766stk/slip-httpd/Make.defs b/nuttx/configs/olimex-lpc1766stk/slip-httpd/Make.defs index 7f7278d06..984d4e187 100644 --- a/nuttx/configs/olimex-lpc1766stk/slip-httpd/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/slip-httpd/Make.defs @@ -120,7 +120,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/olimex-lpc1766stk/thttpd/Make.defs b/nuttx/configs/olimex-lpc1766stk/thttpd/Make.defs index 96270bc28..11e155ed8 100644 --- a/nuttx/configs/olimex-lpc1766stk/thttpd/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/thttpd/Make.defs @@ -120,7 +120,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/olimex-lpc1766stk/usbserial/Make.defs b/nuttx/configs/olimex-lpc1766stk/usbserial/Make.defs index 2d7321efd..1cedb01d7 100644 --- a/nuttx/configs/olimex-lpc1766stk/usbserial/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/usbserial/Make.defs @@ -117,7 +117,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/olimex-lpc1766stk/usbstorage/Make.defs b/nuttx/configs/olimex-lpc1766stk/usbstorage/Make.defs index 8c62990ae..f879340f1 100644 --- a/nuttx/configs/olimex-lpc1766stk/usbstorage/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/usbstorage/Make.defs @@ -117,7 +117,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/olimex-lpc1766stk/wlan/Make.defs b/nuttx/configs/olimex-lpc1766stk/wlan/Make.defs index 593d5f939..a316a0e6a 100644 --- a/nuttx/configs/olimex-lpc1766stk/wlan/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/wlan/Make.defs @@ -117,7 +117,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/olimex-lpc2378/nsh/Make.defs b/nuttx/configs/olimex-lpc2378/nsh/Make.defs index 2821aa73c..022f3670b 100644 --- a/nuttx/configs/olimex-lpc2378/nsh/Make.defs +++ b/nuttx/configs/olimex-lpc2378/nsh/Make.defs @@ -129,7 +129,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld \ + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld \ -no-check-sections LDNXFLATFLAGS = -e main -s 2048 diff --git a/nuttx/configs/olimex-lpc2378/ostest/Make.defs b/nuttx/configs/olimex-lpc2378/ostest/Make.defs index 69be8db5b..043f7ad8e 100644 --- a/nuttx/configs/olimex-lpc2378/ostest/Make.defs +++ b/nuttx/configs/olimex-lpc2378/ostest/Make.defs @@ -129,7 +129,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld \ + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld \ -no-check-sections LDNXFLATFLAGS = -e main -s 2048 diff --git a/nuttx/configs/olimex-stm32-p107/nsh/Make.defs b/nuttx/configs/olimex-stm32-p107/nsh/Make.defs index 5175c2f8f..3314a82be 100644 --- a/nuttx/configs/olimex-stm32-p107/nsh/Make.defs +++ b/nuttx/configs/olimex-stm32-p107/nsh/Make.defs @@ -129,7 +129,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/olimex-stm32-p107/ostest/Make.defs b/nuttx/configs/olimex-stm32-p107/ostest/Make.defs index 28c9ab813..fdceac03b 100644 --- a/nuttx/configs/olimex-stm32-p107/ostest/Make.defs +++ b/nuttx/configs/olimex-stm32-p107/ostest/Make.defs @@ -129,7 +129,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/olimex-strp711/nettest/Make.defs b/nuttx/configs/olimex-strp711/nettest/Make.defs index e4b8a9852..1c751be09 100644 --- a/nuttx/configs/olimex-strp711/nettest/Make.defs +++ b/nuttx/configs/olimex-strp711/nettest/Make.defs @@ -110,7 +110,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld \ + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld \ -no-check-sections LDNXFLATFLAGS = -e main -s 2048 diff --git a/nuttx/configs/olimex-strp711/nsh/Make.defs b/nuttx/configs/olimex-strp711/nsh/Make.defs index 9ef265d0e..d2c674d3a 100644 --- a/nuttx/configs/olimex-strp711/nsh/Make.defs +++ b/nuttx/configs/olimex-strp711/nsh/Make.defs @@ -110,7 +110,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld \ + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld \ -no-check-sections LDNXFLATFLAGS = -e main -s 2048 diff --git a/nuttx/configs/olimex-strp711/ostest/Make.defs b/nuttx/configs/olimex-strp711/ostest/Make.defs index f4bb09d99..37adf602a 100644 --- a/nuttx/configs/olimex-strp711/ostest/Make.defs +++ b/nuttx/configs/olimex-strp711/ostest/Make.defs @@ -110,7 +110,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld \ + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld \ -no-check-sections LDNXFLATFLAGS = -e main -s 2048 diff --git a/nuttx/configs/pcblogic-pic32mx/nsh/Make.defs b/nuttx/configs/pcblogic-pic32mx/nsh/Make.defs index ecc50dc29..9608ce0ee 100644 --- a/nuttx/configs/pcblogic-pic32mx/nsh/Make.defs +++ b/nuttx/configs/pcblogic-pic32mx/nsh/Make.defs @@ -118,7 +118,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/pcblogic-pic32mx/ostest/Make.defs b/nuttx/configs/pcblogic-pic32mx/ostest/Make.defs index 31be1dc8d..0376ee339 100644 --- a/nuttx/configs/pcblogic-pic32mx/ostest/Make.defs +++ b/nuttx/configs/pcblogic-pic32mx/ostest/Make.defs @@ -118,7 +118,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/pic32-starterkit/nsh/Make.defs b/nuttx/configs/pic32-starterkit/nsh/Make.defs index 9f8762bf7..962801567 100644 --- a/nuttx/configs/pic32-starterkit/nsh/Make.defs +++ b/nuttx/configs/pic32-starterkit/nsh/Make.defs @@ -118,7 +118,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/pic32-starterkit/nsh2/Make.defs b/nuttx/configs/pic32-starterkit/nsh2/Make.defs index 08be39d39..2068db849 100644 --- a/nuttx/configs/pic32-starterkit/nsh2/Make.defs +++ b/nuttx/configs/pic32-starterkit/nsh2/Make.defs @@ -118,7 +118,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/pic32-starterkit/ostest/Make.defs b/nuttx/configs/pic32-starterkit/ostest/Make.defs index d00518b98..370ac7f1f 100644 --- a/nuttx/configs/pic32-starterkit/ostest/Make.defs +++ b/nuttx/configs/pic32-starterkit/ostest/Make.defs @@ -118,7 +118,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/pic32mx7mmb/nsh/Make.defs b/nuttx/configs/pic32mx7mmb/nsh/Make.defs index 608a31442..ed776bc19 100644 --- a/nuttx/configs/pic32mx7mmb/nsh/Make.defs +++ b/nuttx/configs/pic32mx7mmb/nsh/Make.defs @@ -118,7 +118,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/pic32mx7mmb/ostest/Make.defs b/nuttx/configs/pic32mx7mmb/ostest/Make.defs index a203f30e9..54806fb95 100644 --- a/nuttx/configs/pic32mx7mmb/ostest/Make.defs +++ b/nuttx/configs/pic32mx7mmb/ostest/Make.defs @@ -118,7 +118,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/sam3u-ek/README.txt b/nuttx/configs/sam3u-ek/README.txt index b13c68945..91f882409 100644 --- a/nuttx/configs/sam3u-ek/README.txt +++ b/nuttx/configs/sam3u-ek/README.txt @@ -172,12 +172,14 @@ NuttX OABI "buildroot" Toolchain configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI configuration such as cortexm3-defconfig-4.3.3 - 2. Modify the Make.defs file to use the OABI converntions: + 2. Modify the Make.defs file to use the OABI conventions: +CROSSDEV = arm-nuttx-elf- +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections -CROSSDEV = arm-nuttx-eabi- -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections NXFLAT Toolchain ^^^^^^^^^^^^^^^^ diff --git a/nuttx/configs/sam3u-ek/knsh/Make.defs b/nuttx/configs/sam3u-ek/knsh/Make.defs index f65420bcf..a402a4d51 100644 --- a/nuttx/configs/sam3u-ek/knsh/Make.defs +++ b/nuttx/configs/sam3u-ek/knsh/Make.defs @@ -117,7 +117,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/sam3u-ek/nsh/Make.defs b/nuttx/configs/sam3u-ek/nsh/Make.defs index c73b1f785..5bf989aad 100644 --- a/nuttx/configs/sam3u-ek/nsh/Make.defs +++ b/nuttx/configs/sam3u-ek/nsh/Make.defs @@ -117,7 +117,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/sam3u-ek/nx/Make.defs b/nuttx/configs/sam3u-ek/nx/Make.defs index 31b440781..e4140a110 100644 --- a/nuttx/configs/sam3u-ek/nx/Make.defs +++ b/nuttx/configs/sam3u-ek/nx/Make.defs @@ -117,7 +117,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/sam3u-ek/ostest/Make.defs b/nuttx/configs/sam3u-ek/ostest/Make.defs index 9fcea29f6..8c765976b 100644 --- a/nuttx/configs/sam3u-ek/ostest/Make.defs +++ b/nuttx/configs/sam3u-ek/ostest/Make.defs @@ -117,7 +117,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/sam3u-ek/touchscreen/Make.defs b/nuttx/configs/sam3u-ek/touchscreen/Make.defs index fb8ab9358..99410a652 100644 --- a/nuttx/configs/sam3u-ek/touchscreen/Make.defs +++ b/nuttx/configs/sam3u-ek/touchscreen/Make.defs @@ -117,7 +117,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/shenzhou/README.txt b/nuttx/configs/shenzhou/README.txt index c04c55ad0..ff4cf7450 100644 --- a/nuttx/configs/shenzhou/README.txt +++ b/nuttx/configs/shenzhou/README.txt @@ -40,7 +40,9 @@ Contents - Development Environment - GNU Toolchain Options - IDEs - - NuttX buildroot Toolchain + - NuttX EABI buildroot Toolchain + - NuttX OABI buildroot Toolchain + - NXFLAT Toolchain - Shenzhou-specific Configuration Options - LEDs - Shenzhou-specific Configuration Options @@ -330,8 +332,8 @@ IDEs one time from the Cygwin command line in order to obtain the pre-built startup object needed by RIDE. -NuttX buildroot Toolchain -========================= +NuttX EABI buildroot Toolchain +============================== A GNU GCC-based toolchain is assumed. The files */setenv.sh should be modified to point to the correct path to the Cortex-M3 GCC toolchain (if @@ -382,6 +384,58 @@ NuttX buildroot Toolchain detailed PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. +NuttX OABI "buildroot" Toolchain +================================ + + The older, OABI buildroot toolchain is also available. To use the OABI + toolchain: + + 1. When building the buildroot toolchain, either (1) modify the cortexm3-eabi-defconfig-4.6.3 + configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI + configuration such as cortexm3-defconfig-4.3.3 + + 2. Modify the Make.defs file to use the OABI conventions: + + +CROSSDEV = arm-nuttx-elf- + +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections + -CROSSDEV = arm-nuttx-eabi- + -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections + +NXFLAT Toolchain +================ + + If you are *not* using the NuttX buildroot toolchain and you want to use + the NXFLAT tools, then you will still have to build a portion of the buildroot + tools -- just the NXFLAT tools. The buildroot with the NXFLAT tools can + be downloaded from the NuttX SourceForge download site + (https://sourceforge.net/projects/nuttx/files/). + + This GNU toolchain builds and executes in the Linux or Cygwin environment. + + 1. You must have already configured Nuttx in /nuttx. + + cd tools + ./configure.sh lpcxpresso-lpc1768/ + + 2. Download the latest buildroot package into + + 3. unpack the buildroot tarball. The resulting directory may + have versioning information on it like buildroot-x.y.z. If so, + rename /buildroot-x.y.z to /buildroot. + + 4. cd /buildroot + + 5. cp configs/cortexm3-defconfig-nxflat .config + + 6. make oldconfig + + 7. make + + 8. Edit setenv.h, if necessary, so that the PATH variable includes + the path to the newly builtNXFLAT binaries. + LEDs ==== diff --git a/nuttx/configs/shenzhou/nsh/Make.defs b/nuttx/configs/shenzhou/nsh/Make.defs index 588bb2760..2318e6c9c 100644 --- a/nuttx/configs/shenzhou/nsh/Make.defs +++ b/nuttx/configs/shenzhou/nsh/Make.defs @@ -151,7 +151,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/shenzhou/nxwm/Make.defs b/nuttx/configs/shenzhou/nxwm/Make.defs index d94f0c38a..84e0df782 100644 --- a/nuttx/configs/shenzhou/nxwm/Make.defs +++ b/nuttx/configs/shenzhou/nxwm/Make.defs @@ -151,7 +151,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm3210e-eval/README.txt b/nuttx/configs/stm3210e-eval/README.txt index 704fadb62..65f511320 100644 --- a/nuttx/configs/stm3210e-eval/README.txt +++ b/nuttx/configs/stm3210e-eval/README.txt @@ -180,12 +180,14 @@ NuttX OABI "buildroot" Toolchain configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI configuration such as cortexm3-defconfig-4.3.3 - 2. Modify the Make.defs file to use the OABI converntions: + 2. Modify the Make.defs file to use the OABI conventions: +CROSSDEV = arm-nuttx-elf- +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections -CROSSDEV = arm-nuttx-eabi- -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections NXFLAT Toolchain ================ diff --git a/nuttx/configs/stm3210e-eval/RIDE/Make.defs b/nuttx/configs/stm3210e-eval/RIDE/Make.defs index 30dfda704..6e69590c7 100644 --- a/nuttx/configs/stm3210e-eval/RIDE/Make.defs +++ b/nuttx/configs/stm3210e-eval/RIDE/Make.defs @@ -129,7 +129,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm3210e-eval/buttons/Make.defs b/nuttx/configs/stm3210e-eval/buttons/Make.defs index f18619f80..860d81c1f 100644 --- a/nuttx/configs/stm3210e-eval/buttons/Make.defs +++ b/nuttx/configs/stm3210e-eval/buttons/Make.defs @@ -129,7 +129,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm3210e-eval/composite/Make.defs b/nuttx/configs/stm3210e-eval/composite/Make.defs index 848663573..c0d85bf22 100644 --- a/nuttx/configs/stm3210e-eval/composite/Make.defs +++ b/nuttx/configs/stm3210e-eval/composite/Make.defs @@ -129,7 +129,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm3210e-eval/nsh/Make.defs b/nuttx/configs/stm3210e-eval/nsh/Make.defs index e3e4888fe..03d19fbc8 100644 --- a/nuttx/configs/stm3210e-eval/nsh/Make.defs +++ b/nuttx/configs/stm3210e-eval/nsh/Make.defs @@ -129,7 +129,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm3210e-eval/nsh2/Make.defs b/nuttx/configs/stm3210e-eval/nsh2/Make.defs index 330516696..f84c11552 100644 --- a/nuttx/configs/stm3210e-eval/nsh2/Make.defs +++ b/nuttx/configs/stm3210e-eval/nsh2/Make.defs @@ -129,7 +129,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm3210e-eval/nx/Make.defs b/nuttx/configs/stm3210e-eval/nx/Make.defs index 6aaa6644b..7f253873a 100644 --- a/nuttx/configs/stm3210e-eval/nx/Make.defs +++ b/nuttx/configs/stm3210e-eval/nx/Make.defs @@ -129,7 +129,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm3210e-eval/nxconsole/Make.defs b/nuttx/configs/stm3210e-eval/nxconsole/Make.defs index 7b2be02a5..8993a53aa 100644 --- a/nuttx/configs/stm3210e-eval/nxconsole/Make.defs +++ b/nuttx/configs/stm3210e-eval/nxconsole/Make.defs @@ -131,7 +131,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm3210e-eval/nxlines/Make.defs b/nuttx/configs/stm3210e-eval/nxlines/Make.defs index 1469658a0..190ed098f 100644 --- a/nuttx/configs/stm3210e-eval/nxlines/Make.defs +++ b/nuttx/configs/stm3210e-eval/nxlines/Make.defs @@ -131,7 +131,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm3210e-eval/nxtext/Make.defs b/nuttx/configs/stm3210e-eval/nxtext/Make.defs index b130e5622..d4f8ec2fe 100644 --- a/nuttx/configs/stm3210e-eval/nxtext/Make.defs +++ b/nuttx/configs/stm3210e-eval/nxtext/Make.defs @@ -131,7 +131,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm3210e-eval/ostest/Make.defs b/nuttx/configs/stm3210e-eval/ostest/Make.defs index bd50d3b69..ef1a3d423 100644 --- a/nuttx/configs/stm3210e-eval/ostest/Make.defs +++ b/nuttx/configs/stm3210e-eval/ostest/Make.defs @@ -129,7 +129,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm3210e-eval/pm/Make.defs b/nuttx/configs/stm3210e-eval/pm/Make.defs index 6ad7e3a4c..a60e4a774 100644 --- a/nuttx/configs/stm3210e-eval/pm/Make.defs +++ b/nuttx/configs/stm3210e-eval/pm/Make.defs @@ -129,7 +129,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm3210e-eval/usbserial/Make.defs b/nuttx/configs/stm3210e-eval/usbserial/Make.defs index 586c361a9..f08d5b68c 100644 --- a/nuttx/configs/stm3210e-eval/usbserial/Make.defs +++ b/nuttx/configs/stm3210e-eval/usbserial/Make.defs @@ -129,7 +129,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm3210e-eval/usbstorage/Make.defs b/nuttx/configs/stm3210e-eval/usbstorage/Make.defs index c305b42c9..7f2cb73b6 100644 --- a/nuttx/configs/stm3210e-eval/usbstorage/Make.defs +++ b/nuttx/configs/stm3210e-eval/usbstorage/Make.defs @@ -129,7 +129,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm3220g-eval/README.txt b/nuttx/configs/stm3220g-eval/README.txt index 79311150d..36fd75d25 100644 --- a/nuttx/configs/stm3220g-eval/README.txt +++ b/nuttx/configs/stm3220g-eval/README.txt @@ -219,12 +219,14 @@ NuttX OABI "buildroot" Toolchain configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI configuration such as cortexm3-defconfig-4.3.3 - 2. Modify the Make.defs file to use the OABI converntions: + 2. Modify the Make.defs file to use the OABI conventions: +CROSSDEV = arm-nuttx-elf- +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections -CROSSDEV = arm-nuttx-eabi- -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections NXFLAT Toolchain ================ diff --git a/nuttx/configs/stm3220g-eval/dhcpd/Make.defs b/nuttx/configs/stm3220g-eval/dhcpd/Make.defs index 3f2c4e066..e8bb28c76 100644 --- a/nuttx/configs/stm3220g-eval/dhcpd/Make.defs +++ b/nuttx/configs/stm3220g-eval/dhcpd/Make.defs @@ -153,7 +153,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm3220g-eval/nettest/Make.defs b/nuttx/configs/stm3220g-eval/nettest/Make.defs index c6b2f895b..2c6b8a1f4 100644 --- a/nuttx/configs/stm3220g-eval/nettest/Make.defs +++ b/nuttx/configs/stm3220g-eval/nettest/Make.defs @@ -153,7 +153,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm3220g-eval/nsh/Make.defs b/nuttx/configs/stm3220g-eval/nsh/Make.defs index 3bd7c1528..834db56bc 100644 --- a/nuttx/configs/stm3220g-eval/nsh/Make.defs +++ b/nuttx/configs/stm3220g-eval/nsh/Make.defs @@ -153,7 +153,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm3220g-eval/nsh2/Make.defs b/nuttx/configs/stm3220g-eval/nsh2/Make.defs index dfd41d5c5..f29c47214 100644 --- a/nuttx/configs/stm3220g-eval/nsh2/Make.defs +++ b/nuttx/configs/stm3220g-eval/nsh2/Make.defs @@ -153,7 +153,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm3220g-eval/nxwm/Make.defs b/nuttx/configs/stm3220g-eval/nxwm/Make.defs index 65442d731..4b770ba64 100644 --- a/nuttx/configs/stm3220g-eval/nxwm/Make.defs +++ b/nuttx/configs/stm3220g-eval/nxwm/Make.defs @@ -153,7 +153,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm3220g-eval/ostest/Make.defs b/nuttx/configs/stm3220g-eval/ostest/Make.defs index 270d53339..a67036f78 100644 --- a/nuttx/configs/stm3220g-eval/ostest/Make.defs +++ b/nuttx/configs/stm3220g-eval/ostest/Make.defs @@ -153,7 +153,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm3220g-eval/telnetd/Make.defs b/nuttx/configs/stm3220g-eval/telnetd/Make.defs index 0d7f1a078..4a6927906 100644 --- a/nuttx/configs/stm3220g-eval/telnetd/Make.defs +++ b/nuttx/configs/stm3220g-eval/telnetd/Make.defs @@ -153,7 +153,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm3240g-eval/README.txt b/nuttx/configs/stm3240g-eval/README.txt index d77609e12..6da18b7e5 100644 --- a/nuttx/configs/stm3240g-eval/README.txt +++ b/nuttx/configs/stm3240g-eval/README.txt @@ -226,12 +226,14 @@ NuttX OABI "buildroot" Toolchain configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI configuration such as cortexm3-defconfig-4.3.3 - 2. Modify the Make.defs file to use the OABI converntions: + 2. Modify the Make.defs file to use the OABI conventions: +CROSSDEV = arm-nuttx-elf- +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections -CROSSDEV = arm-nuttx-eabi- -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections NXFLAT Toolchain ================ diff --git a/nuttx/configs/stm3240g-eval/dhcpd/Make.defs b/nuttx/configs/stm3240g-eval/dhcpd/Make.defs index e84648b10..5b1334a07 100644 --- a/nuttx/configs/stm3240g-eval/dhcpd/Make.defs +++ b/nuttx/configs/stm3240g-eval/dhcpd/Make.defs @@ -153,7 +153,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm3240g-eval/discover/Make.defs b/nuttx/configs/stm3240g-eval/discover/Make.defs index 561bed1e0..58afd3903 100644 --- a/nuttx/configs/stm3240g-eval/discover/Make.defs +++ b/nuttx/configs/stm3240g-eval/discover/Make.defs @@ -153,7 +153,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm3240g-eval/nettest/Make.defs b/nuttx/configs/stm3240g-eval/nettest/Make.defs index 71764aa24..a7e4f9e07 100644 --- a/nuttx/configs/stm3240g-eval/nettest/Make.defs +++ b/nuttx/configs/stm3240g-eval/nettest/Make.defs @@ -153,7 +153,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm3240g-eval/nsh/Make.defs b/nuttx/configs/stm3240g-eval/nsh/Make.defs index 71da0724a..d63876e75 100644 --- a/nuttx/configs/stm3240g-eval/nsh/Make.defs +++ b/nuttx/configs/stm3240g-eval/nsh/Make.defs @@ -153,7 +153,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm3240g-eval/nsh2/Make.defs b/nuttx/configs/stm3240g-eval/nsh2/Make.defs index 51aaf553e..16fef3344 100644 --- a/nuttx/configs/stm3240g-eval/nsh2/Make.defs +++ b/nuttx/configs/stm3240g-eval/nsh2/Make.defs @@ -153,7 +153,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm3240g-eval/nxconsole/Make.defs b/nuttx/configs/stm3240g-eval/nxconsole/Make.defs index 34865b5c2..20fabfc9d 100644 --- a/nuttx/configs/stm3240g-eval/nxconsole/Make.defs +++ b/nuttx/configs/stm3240g-eval/nxconsole/Make.defs @@ -153,7 +153,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm3240g-eval/nxwm/Make.defs b/nuttx/configs/stm3240g-eval/nxwm/Make.defs index b15333c96..bf2da3246 100644 --- a/nuttx/configs/stm3240g-eval/nxwm/Make.defs +++ b/nuttx/configs/stm3240g-eval/nxwm/Make.defs @@ -153,7 +153,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm3240g-eval/ostest/Make.defs b/nuttx/configs/stm3240g-eval/ostest/Make.defs index 768a095f8..c984a7e85 100644 --- a/nuttx/configs/stm3240g-eval/ostest/Make.defs +++ b/nuttx/configs/stm3240g-eval/ostest/Make.defs @@ -153,7 +153,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm3240g-eval/telnetd/Make.defs b/nuttx/configs/stm3240g-eval/telnetd/Make.defs index 8255e0767..498ee3386 100644 --- a/nuttx/configs/stm3240g-eval/telnetd/Make.defs +++ b/nuttx/configs/stm3240g-eval/telnetd/Make.defs @@ -153,7 +153,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm3240g-eval/webserver/Make.defs b/nuttx/configs/stm3240g-eval/webserver/Make.defs index 855ca4186..fb47d4005 100644 --- a/nuttx/configs/stm3240g-eval/webserver/Make.defs +++ b/nuttx/configs/stm3240g-eval/webserver/Make.defs @@ -152,7 +152,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm3240g-eval/xmlrpc/Make.defs b/nuttx/configs/stm3240g-eval/xmlrpc/Make.defs index dab94db50..8f7fe96dc 100644 --- a/nuttx/configs/stm3240g-eval/xmlrpc/Make.defs +++ b/nuttx/configs/stm3240g-eval/xmlrpc/Make.defs @@ -153,7 +153,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm32f4discovery/README.txt b/nuttx/configs/stm32f4discovery/README.txt index 65b4bf752..2054e90c6 100644 --- a/nuttx/configs/stm32f4discovery/README.txt +++ b/nuttx/configs/stm32f4discovery/README.txt @@ -223,12 +223,14 @@ NuttX OABI "buildroot" Toolchain configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI configuration such as cortexm3-defconfig-4.3.3 - 2. Modify the Make.defs file to use the OABI converntions: + 2. Modify the Make.defs file to use the OABI conventions: +CROSSDEV = arm-nuttx-elf- +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections -CROSSDEV = arm-nuttx-eabi- -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections NXFLAT Toolchain ================ diff --git a/nuttx/configs/stm32f4discovery/nsh/Make.defs b/nuttx/configs/stm32f4discovery/nsh/Make.defs index bab095abc..ed1662af5 100644 --- a/nuttx/configs/stm32f4discovery/nsh/Make.defs +++ b/nuttx/configs/stm32f4discovery/nsh/Make.defs @@ -153,7 +153,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm32f4discovery/nxlines/Make.defs b/nuttx/configs/stm32f4discovery/nxlines/Make.defs index 042da6a92..cfdb79a74 100644 --- a/nuttx/configs/stm32f4discovery/nxlines/Make.defs +++ b/nuttx/configs/stm32f4discovery/nxlines/Make.defs @@ -153,7 +153,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm32f4discovery/ostest/Make.defs b/nuttx/configs/stm32f4discovery/ostest/Make.defs index 10025ad9d..6ed8530ad 100644 --- a/nuttx/configs/stm32f4discovery/ostest/Make.defs +++ b/nuttx/configs/stm32f4discovery/ostest/Make.defs @@ -153,7 +153,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/stm32f4discovery/pm/Make.defs b/nuttx/configs/stm32f4discovery/pm/Make.defs index 1a67f1b8c..3643548d4 100644 --- a/nuttx/configs/stm32f4discovery/pm/Make.defs +++ b/nuttx/configs/stm32f4discovery/pm/Make.defs @@ -153,7 +153,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/sure-pic32mx/nsh/Make.defs b/nuttx/configs/sure-pic32mx/nsh/Make.defs index ac6df4056..debf622d2 100644 --- a/nuttx/configs/sure-pic32mx/nsh/Make.defs +++ b/nuttx/configs/sure-pic32mx/nsh/Make.defs @@ -118,7 +118,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/sure-pic32mx/ostest/Make.defs b/nuttx/configs/sure-pic32mx/ostest/Make.defs index ac93ceeb0..0c8d4346a 100644 --- a/nuttx/configs/sure-pic32mx/ostest/Make.defs +++ b/nuttx/configs/sure-pic32mx/ostest/Make.defs @@ -118,7 +118,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/sure-pic32mx/usbnsh/Make.defs b/nuttx/configs/sure-pic32mx/usbnsh/Make.defs index 8faadcf96..fa8d3700f 100644 --- a/nuttx/configs/sure-pic32mx/usbnsh/Make.defs +++ b/nuttx/configs/sure-pic32mx/usbnsh/Make.defs @@ -118,7 +118,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/teensy/hello/Make.defs b/nuttx/configs/teensy/hello/Make.defs index cca88363c..b79a52ed9 100644 --- a/nuttx/configs/teensy/hello/Make.defs +++ b/nuttx/configs/teensy/hello/Make.defs @@ -107,7 +107,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/teensy/nsh/Make.defs b/nuttx/configs/teensy/nsh/Make.defs index 13f8e7902..65838649c 100644 --- a/nuttx/configs/teensy/nsh/Make.defs +++ b/nuttx/configs/teensy/nsh/Make.defs @@ -107,7 +107,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/teensy/usbstorage/Make.defs b/nuttx/configs/teensy/usbstorage/Make.defs index 706daf81f..fa2997fb0 100644 --- a/nuttx/configs/teensy/usbstorage/Make.defs +++ b/nuttx/configs/teensy/usbstorage/Make.defs @@ -107,7 +107,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/twr-k60n512/README.txt b/nuttx/configs/twr-k60n512/README.txt index 3ac70cf7e..27644deae 100644 --- a/nuttx/configs/twr-k60n512/README.txt +++ b/nuttx/configs/twr-k60n512/README.txt @@ -437,12 +437,14 @@ NuttX OABI "buildroot" Toolchain configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI configuration such as cortexm3-defconfig-4.3.3 - 2. Modify the Make.defs file to use the OABI converntions: + 2. Modify the Make.defs file to use the OABI conventions: +CROSSDEV = arm-nuttx-elf- +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections -CROSSDEV = arm-nuttx-eabi- -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections NXFLAT Toolchain ================ diff --git a/nuttx/configs/twr-k60n512/nsh/Make.defs b/nuttx/configs/twr-k60n512/nsh/Make.defs index 7bb9f09d4..f2922c575 100644 --- a/nuttx/configs/twr-k60n512/nsh/Make.defs +++ b/nuttx/configs/twr-k60n512/nsh/Make.defs @@ -117,7 +117,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/twr-k60n512/ostest/Make.defs b/nuttx/configs/twr-k60n512/ostest/Make.defs index 9254223dc..871141640 100644 --- a/nuttx/configs/twr-k60n512/ostest/Make.defs +++ b/nuttx/configs/twr-k60n512/ostest/Make.defs @@ -117,7 +117,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/ubw32/nsh/Make.defs b/nuttx/configs/ubw32/nsh/Make.defs index ca73b9def..07a966446 100644 --- a/nuttx/configs/ubw32/nsh/Make.defs +++ b/nuttx/configs/ubw32/nsh/Make.defs @@ -118,7 +118,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/ubw32/ostest/Make.defs b/nuttx/configs/ubw32/ostest/Make.defs index 739d78075..4f2971768 100644 --- a/nuttx/configs/ubw32/ostest/Make.defs +++ b/nuttx/configs/ubw32/ostest/Make.defs @@ -118,7 +118,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/configs/vsn/README.txt b/nuttx/configs/vsn/README.txt index b05ffa5dd..ae5f374dd 100644 --- a/nuttx/configs/vsn/README.txt +++ b/nuttx/configs/vsn/README.txt @@ -177,12 +177,14 @@ NuttX OABI "buildroot" Toolchain configuration to use EABI (using 'make menuconfig'), or (2) use an exising OABI configuration such as cortexm3-defconfig-4.3.3 - 2. Modify the Make.defs file to use the OABI converntions: + 2. Modify the Make.defs file to use the OABI conventions: +CROSSDEV = arm-nuttx-elf- +ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections -CROSSDEV = arm-nuttx-eabi- -ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections NXFLAT Toolchain ^^^^^^^^^^^^^^^^ diff --git a/nuttx/configs/vsn/nsh/Make.defs b/nuttx/configs/vsn/nsh/Make.defs index 292abcc72..64b972ee2 100644 --- a/nuttx/configs/vsn/nsh/Make.defs +++ b/nuttx/configs/vsn/nsh/Make.defs @@ -129,7 +129,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o -- cgit v1.2.3 From 6cb1bc7e67e65faecdafc169b0f897645bb8ea83 Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 10 Oct 2012 17:17:50 +0000 Subject: Oop. Part of last change was still in the editor git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5226 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/binfmt/libnxflat/gnu-nxflat-pcrel.ld | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) (limited to 'nuttx') diff --git a/nuttx/binfmt/libnxflat/gnu-nxflat-pcrel.ld b/nuttx/binfmt/libnxflat/gnu-nxflat-pcrel.ld index eb79023d0..71e4399ba 100644 --- a/nuttx/binfmt/libnxflat/gnu-nxflat-pcrel.ld +++ b/nuttx/binfmt/libnxflat/gnu-nxflat-pcrel.ld @@ -97,6 +97,15 @@ SECTIONS *(.call_table_data) *(.call_table_text) + /* In this model, .rodata is access using PC-relative addressing + * and, hence, must also reside in the .text section. + */ + + *(.rodata) + *(.rodata1) + *(.rodata.*) + *(.gnu.linkonce.r*) + _etext = . ; } > ISPACE @@ -108,10 +117,6 @@ SECTIONS .data 0x00000000 : { __data_start = . ; - *(.rodata) - *(.rodata1) - *(.rodata.*) - *(.gnu.linkonce.r*) *(.data) *(.data1) *(.data.*) -- cgit v1.2.3 From b71fcbb0de3d1e1ad8011303ade8bc38c83486d2 Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 10 Oct 2012 19:36:32 +0000 Subject: More fixes for ldnxflat. There are still problems with the GCC 4.6.3 git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5227 42af7a65-404d-4744-a932-0658087f49c3 --- misc/buildroot/ChangeLog | 3 + misc/buildroot/toolchain/nxflat/ldnxflat.c | 97 ++++++++++++++++++++++++----- nuttx/Documentation/NuttXNxFlat.html | 2 +- nuttx/TODO | 42 ++++++++++++- nuttx/binfmt/libnxflat/gnu-nxflat-gotoff.ld | 5 ++ 5 files changed, 131 insertions(+), 18 deletions(-) (limited to 'nuttx') diff --git a/misc/buildroot/ChangeLog b/misc/buildroot/ChangeLog index 3cfd60bf2..cdbef5da1 100644 --- a/misc/buildroot/ChangeLog +++ b/misc/buildroot/ChangeLog @@ -123,4 +123,7 @@ buildroot-1.11 2011-xx-xx type was not generated by GCC/LD prior to gcc-4.6.3 * R_ARM_REL32 logic is conditionally disabled because it has not been tested. + * ldnxflat: Correct a memory allocation error that could cause written + past the end of allocated memory. Partial restoration of R_ARM_REL32 + logic. There are lots of issues that I still do not understand here. diff --git a/misc/buildroot/toolchain/nxflat/ldnxflat.c b/misc/buildroot/toolchain/nxflat/ldnxflat.c index 5343e6b43..39fc98ce9 100644 --- a/misc/buildroot/toolchain/nxflat/ldnxflat.c +++ b/misc/buildroot/toolchain/nxflat/ldnxflat.c @@ -800,11 +800,83 @@ static void alloc_got_entry(asymbol *sym) } /*********************************************************************** - * relocate_arm32 + * relocate_rel32 ***********************************************************************/ static void -relocate_arm32(arelent *relp, int32_t *target, symvalue sym_value) +relocate_rel32(arelent *relp, int32_t *target, symvalue sym_value) +{ + reloc_howto_type *how_to = relp->howto; + asymbol *rel_sym = *relp->sym_ptr_ptr; + asection *rel_section = rel_sym->section; + int32_t value; + int32_t temp; + int32_t saved; + int reloc_type; + + if (verbose > 1) + { + vdbg(" Original location %p is %08lx ", +#ifdef ARCH_BIG_ENDIAN + target, (long)nxflat_swap32(*target)); +#else + target, (long)*target); +#endif + if (verbose > 2) + { + printf("rsh %d ", how_to->rightshift); + printf(" sz %d ", how_to->size); + printf("bit %d ", how_to->bitsize); + printf("rel %d ", how_to->pc_relative); + printf("smask %08lx ", (long)how_to->src_mask); + printf("dmask %08lx ", (long)how_to->dst_mask); + printf("off %d ", how_to->pcrel_offset); + } + + printf("\n"); + } + +#ifdef ARCH_BIG_ENDIAN + saved = temp = (int32_t) nxflat_swap32(*target); +#else + saved = temp = *target; +#endif + /* Mask and sign extend */ + + temp &= how_to->src_mask; + temp <<= (32 - how_to->bitsize); + temp >>= (32 - how_to->bitsize); + + /* Calculate the new value: Current value + VMA - current PC */ + + value = temp + sym_value + rel_section->vma - relp->address; + + /* Offset */ + + temp += (value >> how_to->rightshift); + + /* Mask upper bits from rollover */ + + temp &= how_to->dst_mask; + + /* Replace data that was masked */ + + temp |= saved & (~how_to->dst_mask); + + vdbg(" Modified location: %08lx\n", (long)temp); +#ifdef ARCH_BIG_ENDIAN + *target = (long)nxflat_swap32(temp); +#else + *target = (long)temp; +#endif + } + +/*********************************************************************** + * relocate_abs32 + ***********************************************************************/ + +static void +relocate_abs32(arelent *relp, int32_t *target, symvalue sym_value) { reloc_howto_type *how_to = relp->howto; asymbol *rel_sym = *relp->sym_ptr_ptr; @@ -901,7 +973,7 @@ relocate_arm32(arelent *relp, int32_t *target, symvalue sym_value) /* Re-allocate memory to include this relocation */ relocs = (struct nxflat_reloc_s*) - realloc(nxflat_relocs, sizeof(struct nxflat_reloc_s) * nxflat_nrelocs + 1); + realloc(nxflat_relocs, sizeof(struct nxflat_reloc_s) * (nxflat_nrelocs + 1)); if (!relocs) { err("Failed to re-allocate memory ABS32 relocations (%d relocations)\n", @@ -1105,7 +1177,7 @@ resolve_segment_relocs(bfd *input_bfd, segment_info *inf, asymbol **syms) dbg("Performing ABS32 link at addr %08lx [%08lx] to sym '%s' [%08lx]\n", (long)relpp[j]->address, (long)*target, rel_sym->name, (long)sym_value); - relocate_arm32(relpp[j], target, sym_value); + relocate_abs32(relpp[j], target, sym_value); } break; @@ -1114,18 +1186,12 @@ resolve_segment_relocs(bfd *input_bfd, segment_info *inf, asymbol **syms) dbg("Performing REL32 link at addr %08lx [%08lx] to sym '%s' [%08lx]\n", (long)relpp[j]->address, (long)*target, rel_sym->name, (long)sym_value); - /* The REL32 relocation is just like the ABS32 relocation except that (1) - * the symbol value is relative to the PC, and (2) we cannot permit - * REL32 relocations to data in I-Space. That just would not make sense. - */ -#if 1 - /* The logic below may or may not be correct. It has not been verified - * so, for now, it is disabled. + /* The only valid REL32 relocation would be to relocate a reference from + * I-Space to another symbol in I-Space. That should be handled by the + * partially linking logic so we don't expect to see any R_ARM_REL32 + * relocations here. */ - err("REL32 relocation not yet supported\n"); - nerrors++; -#else switch (get_reloc_type(rel_section, NULL)) { case NXFLAT_RELOC_TARGET_UNKNOWN: @@ -1148,11 +1214,10 @@ resolve_segment_relocs(bfd *input_bfd, segment_info *inf, asymbol **syms) case NXFLAT_RELOC_TARGET_TEXT: { vdbg("Symbol '%s' lies in I-Space\n", rel_sym->name); - relocate_arm32(relpp[j], target, sym_value - relpp[j]->address); + relocate_rel32(relpp[j], target, sym_value - relpp[j]->address); } break; } -#endif } break; diff --git a/nuttx/Documentation/NuttXNxFlat.html b/nuttx/Documentation/NuttXNxFlat.html index 4d70ed9c3..c51e3b6a1 100644 --- a/nuttx/Documentation/NuttXNxFlat.html +++ b/nuttx/Documentation/NuttXNxFlat.html @@ -522,7 +522,7 @@ cat ../syscall/syscall.csv ../lib/lib.csv | sort >tmp.csv

                          NOTE: - There are two linker scripts located at binfmt/libnxflat/gnu-nxflat-gotoff.ld. + There are two linker scripts located at binfmt/libnxflat/.

                          1. diff --git a/nuttx/TODO b/nuttx/TODO index 30015ef50..90333c74c 100644 --- a/nuttx/TODO +++ b/nuttx/TODO @@ -12,7 +12,7 @@ nuttx/ (2) Signals (sched/, arch/) (2) pthreads (sched/) (2) C++ Support - (5) Binary loaders (binfmt/) + (6) Binary loaders (binfmt/) (17) Network (net/, drivers/net) (3) USB (drivers/usbdev, drivers/usbhost) (11) Libraries (lib/) @@ -395,6 +395,46 @@ o Binary loaders (binfmt/) Priority: There are too many references like the above. They will have to get fixed as needed for Windows native tool builds. + Title: TOOLCHAIN COMPATIBILITY PROBLEM + Descripton: The older 4.3.3 compiler generates GOTOFF relocations to the constant + strings, like: + + .L3: + .word .LC0(GOTOFF) + .word .LC1(GOTOFF) + .word .LC2(GOTOFF) + .word .LC3(GOTOFF) + .word .LC4(GOTOFF) + + Where .LC0, LC1, LC2, LC3, and .LC4 are the labels correponding to strings in + the .rodata.str1.1 section. One consequence of this is that .rodata must reside + in D-Space since it will addressed relative to the GOT (see the section entitled + "Read-Only Data in RAM" at + http://nuttx.org/Documentation/NuttXNxFlat.html#limitations). + + The newer 4.6.3compiler generated PC relative relocations to the strings: + + .L2: + .word .LC0-(.LPIC0+4) + .word .LC1-(.LPIC1+4) + .word .LC2-(.LPIC2+4) + .word .LC3-(.LPIC4+4) + .word .LC4-(.LPIC5+4) + + This is good and bad. This is good because it means that .rodata.str1.1 can not + reside in FLASH with .text and can be accessed using PC-relative addressing. + That can be accomplished by simply moving the .rodata from the .data section to + the .text section in the linker script. (The NXFLAT linker script is located at + nuttx/binfmt/libnxflat/gnu-nxflat.ld). + + This is bad because a lot of stuff may get broken an a lot of test will need to + be done. One question that I have is does this apply to all kinds of .rodata? + Or just to .rodata.str1.1? + + Status: Open. Many of the required changes are in place but, unfortunately, not enought + go be fully functional. + Priority: Medium. The workaround for now is to use the older, 4.3.3 OABI compiler. + o Network (net/, drivers/net) ^^^^^^^^^^^^^^^^^^^^^^^^^^^ diff --git a/nuttx/binfmt/libnxflat/gnu-nxflat-gotoff.ld b/nuttx/binfmt/libnxflat/gnu-nxflat-gotoff.ld index c0487212a..47debd663 100644 --- a/nuttx/binfmt/libnxflat/gnu-nxflat-gotoff.ld +++ b/nuttx/binfmt/libnxflat/gnu-nxflat-gotoff.ld @@ -107,11 +107,16 @@ SECTIONS .data 0x00000000 : { + /* In this model, .rodata is access using PC-relative addressing + * and, hence, must also reside in the .text section. + */ + __data_start = . ; *(.rodata) *(.rodata1) *(.rodata.*) *(.gnu.linkonce.r*) + *(.data) *(.data1) *(.data.*) -- cgit v1.2.3 From ca71c149e2a6d8c0b7c2aca8ae8c8571ab8d8a59 Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 10 Oct 2012 19:58:57 +0000 Subject: Document problem with GCC 4.8.3 and the NXFLAT tools git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5228 42af7a65-404d-4744-a932-0658087f49c3 --- misc/buildroot/toolchain/nxflat/ldnxflat.c | 1 - nuttx/TODO | 6 ++++-- nuttx/configs/eagle100/README.txt | 6 ++++++ nuttx/configs/ekk-lm3s9b96/README.txt | 6 ++++++ nuttx/configs/fire-stm32v2/README.txt | 6 ++++++ nuttx/configs/hymini-stm32v/README.txt | 6 ++++++ nuttx/configs/kwikstik-k40/README.txt | 6 ++++++ nuttx/configs/lincoln60/README.txt | 6 ++++++ nuttx/configs/lm3s6432-s2e/README.txt | 6 ++++++ nuttx/configs/lm3s6965-ek/README.txt | 6 +++++- nuttx/configs/lm3s8962-ek/README.txt | 6 +++++- nuttx/configs/lpc4330-xplorer/README.txt | 6 ++++++ nuttx/configs/lpcxpresso-lpc1768/README.txt | 6 ++++++ nuttx/configs/mbed/README.txt | 6 ++++++ nuttx/configs/nucleus2g/README.txt | 6 ++++++ nuttx/configs/olimex-lpc1766stk/README.txt | 6 ++++++ nuttx/configs/sam3u-ek/README.txt | 6 ++++++ nuttx/configs/shenzhou/README.txt | 6 ++++++ nuttx/configs/stm3210e-eval/README.txt | 6 ++++++ nuttx/configs/stm3220g-eval/README.txt | 6 ++++++ nuttx/configs/stm3240g-eval/README.txt | 6 ++++++ nuttx/configs/stm32f4discovery/README.txt | 6 ++++++ nuttx/configs/twr-k60n512/README.txt | 6 ++++++ nuttx/configs/vsn/README.txt | 6 ++++++ 24 files changed, 134 insertions(+), 5 deletions(-) (limited to 'nuttx') diff --git a/misc/buildroot/toolchain/nxflat/ldnxflat.c b/misc/buildroot/toolchain/nxflat/ldnxflat.c index 39fc98ce9..620df1566 100644 --- a/misc/buildroot/toolchain/nxflat/ldnxflat.c +++ b/misc/buildroot/toolchain/nxflat/ldnxflat.c @@ -812,7 +812,6 @@ relocate_rel32(arelent *relp, int32_t *target, symvalue sym_value) int32_t value; int32_t temp; int32_t saved; - int reloc_type; if (verbose > 1) { diff --git a/nuttx/TODO b/nuttx/TODO index 90333c74c..906601192 100644 --- a/nuttx/TODO +++ b/nuttx/TODO @@ -431,8 +431,10 @@ o Binary loaders (binfmt/) be done. One question that I have is does this apply to all kinds of .rodata? Or just to .rodata.str1.1? - Status: Open. Many of the required changes are in place but, unfortunately, not enought - go be fully functional. + Status: Open. Many of the required changes are in place but, unfortunately, not enough + go be fully functional. I think all of the I-Space-to-I-Space fixes are in place. + However, the generated code also includes PC-relative references to .bss which + just cannot be done. Priority: Medium. The workaround for now is to use the older, 4.3.3 OABI compiler. o Network (net/, drivers/net) diff --git a/nuttx/configs/eagle100/README.txt b/nuttx/configs/eagle100/README.txt index b4bca39cb..d868817cc 100644 --- a/nuttx/configs/eagle100/README.txt +++ b/nuttx/configs/eagle100/README.txt @@ -147,6 +147,12 @@ NuttX EABI "buildroot" Toolchain details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. + NOTE: Unfortunately, the 4.6.3 EABI toolchain is not compatible with the + the NXFLAT tools. See the top-level TODO file (under "Binary loaders") for + more information about this problem. If you plan to use NXFLAT, please do not + use the GCC 4.6.3 EABI toochain; instead use the GCC 4.3.3 OABI toolchain. + See instructions below. + NuttX OABI "buildroot" Toolchain ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ diff --git a/nuttx/configs/ekk-lm3s9b96/README.txt b/nuttx/configs/ekk-lm3s9b96/README.txt index 2ad435477..78fe96ef5 100644 --- a/nuttx/configs/ekk-lm3s9b96/README.txt +++ b/nuttx/configs/ekk-lm3s9b96/README.txt @@ -225,6 +225,12 @@ NuttX EABI "buildroot" Toolchain details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. + NOTE: Unfortunately, the 4.6.3 EABI toolchain is not compatible with the + the NXFLAT tools. See the top-level TODO file (under "Binary loaders") for + more information about this problem. If you plan to use NXFLAT, please do not + use the GCC 4.6.3 EABI toochain; instead use the GCC 4.3.3 OABI toolchain. + See instructions below. + NuttX OABI "buildroot" Toolchain ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ diff --git a/nuttx/configs/fire-stm32v2/README.txt b/nuttx/configs/fire-stm32v2/README.txt index 9e5d94c23..0cf782a94 100644 --- a/nuttx/configs/fire-stm32v2/README.txt +++ b/nuttx/configs/fire-stm32v2/README.txt @@ -347,6 +347,12 @@ NuttX EABI "buildroot" Toolchain details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. + NOTE: Unfortunately, the 4.6.3 EABI toolchain is not compatible with the + the NXFLAT tools. See the top-level TODO file (under "Binary loaders") for + more information about this problem. If you plan to use NXFLAT, please do not + use the GCC 4.6.3 EABI toochain; instead use the GCC 4.3.3 OABI toolchain. + See instructions below. + NuttX OABI "buildroot" Toolchain ================================ diff --git a/nuttx/configs/hymini-stm32v/README.txt b/nuttx/configs/hymini-stm32v/README.txt index 51f3c1fe3..2c8f3a16a 100644 --- a/nuttx/configs/hymini-stm32v/README.txt +++ b/nuttx/configs/hymini-stm32v/README.txt @@ -167,6 +167,12 @@ NuttX EABI "buildroot" Toolchain details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. + NOTE: Unfortunately, the 4.6.3 EABI toolchain is not compatible with the + the NXFLAT tools. See the top-level TODO file (under "Binary loaders") for + more information about this problem. If you plan to use NXFLAT, please do not + use the GCC 4.6.3 EABI toochain; instead use the GCC 4.3.3 OABI toolchain. + See instructions below. + NuttX OABI "buildroot" Toolchain ================================ diff --git a/nuttx/configs/kwikstik-k40/README.txt b/nuttx/configs/kwikstik-k40/README.txt index 246fa912e..7a68fcffa 100644 --- a/nuttx/configs/kwikstik-k40/README.txt +++ b/nuttx/configs/kwikstik-k40/README.txt @@ -290,6 +290,12 @@ NuttX EABI "buildroot" Toolchain details PLUS some special instructions that you will need to follow if you are building a Cortex-M4 toolchain for Cygwin under Windows. + NOTE: Unfortunately, the 4.6.3 EABI toolchain is not compatible with the + the NXFLAT tools. See the top-level TODO file (under "Binary loaders") for + more information about this problem. If you plan to use NXFLAT, please do not + use the GCC 4.6.3 EABI toochain; instead use the GCC 4.3.3 OABI toolchain. + See instructions below. + NuttX OABI "buildroot" Toolchain ================================ diff --git a/nuttx/configs/lincoln60/README.txt b/nuttx/configs/lincoln60/README.txt index 35fe32267..07ca167cd 100644 --- a/nuttx/configs/lincoln60/README.txt +++ b/nuttx/configs/lincoln60/README.txt @@ -189,6 +189,12 @@ NuttX EABI "buildroot" Toolchain details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. + NOTE: Unfortunately, the 4.6.3 EABI toolchain is not compatible with the + the NXFLAT tools. See the top-level TODO file (under "Binary loaders") for + more information about this problem. If you plan to use NXFLAT, please do not + use the GCC 4.6.3 EABI toochain; instead use the GCC 4.3.3 OABI toolchain. + See instructions below. + NuttX OABI "buildroot" Toolchain ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ diff --git a/nuttx/configs/lm3s6432-s2e/README.txt b/nuttx/configs/lm3s6432-s2e/README.txt index 460b5546d..3630ccc5e 100644 --- a/nuttx/configs/lm3s6432-s2e/README.txt +++ b/nuttx/configs/lm3s6432-s2e/README.txt @@ -219,6 +219,12 @@ NuttX EABI "buildroot" Toolchain details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. + NOTE: Unfortunately, the 4.6.3 EABI toolchain is not compatible with the + the NXFLAT tools. See the top-level TODO file (under "Binary loaders") for + more information about this problem. If you plan to use NXFLAT, please do not + use the GCC 4.6.3 EABI toochain; instead use the GCC 4.3.3 OABI toolchain. + See instructions below. + NuttX OABI "buildroot" Toolchain ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ diff --git a/nuttx/configs/lm3s6965-ek/README.txt b/nuttx/configs/lm3s6965-ek/README.txt index 4aba09bee..f6c32ee82 100644 --- a/nuttx/configs/lm3s6965-ek/README.txt +++ b/nuttx/configs/lm3s6965-ek/README.txt @@ -249,7 +249,11 @@ NuttX EABI "buildroot" Toolchain details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. - NOTE: This is an OABI toolchain. + NOTE: Unfortunately, the 4.6.3 EABI toolchain is not compatible with the + the NXFLAT tools. See the top-level TODO file (under "Binary loaders") for + more information about this problem. If you plan to use NXFLAT, please do not + use the GCC 4.6.3 EABI toochain; instead use the GCC 4.3.3 OABI toolchain. + See instructions below. NuttX OABI "buildroot" Toolchain ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ diff --git a/nuttx/configs/lm3s8962-ek/README.txt b/nuttx/configs/lm3s8962-ek/README.txt index 570d158a2..310edabc5 100644 --- a/nuttx/configs/lm3s8962-ek/README.txt +++ b/nuttx/configs/lm3s8962-ek/README.txt @@ -233,7 +233,11 @@ NuttX EABI "buildroot" Toolchain details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. - NOTE: This is an OABI toolchain. + NOTE: Unfortunately, the 4.6.3 EABI toolchain is not compatible with the + the NXFLAT tools. See the top-level TODO file (under "Binary loaders") for + more information about this problem. If you plan to use NXFLAT, please do not + use the GCC 4.6.3 EABI toochain; instead use the GCC 4.3.3 OABI toolchain. + See instructions below. NuttX OABI "buildroot" Toolchain ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ diff --git a/nuttx/configs/lpc4330-xplorer/README.txt b/nuttx/configs/lpc4330-xplorer/README.txt index ea1098be5..8c88b5758 100644 --- a/nuttx/configs/lpc4330-xplorer/README.txt +++ b/nuttx/configs/lpc4330-xplorer/README.txt @@ -501,6 +501,12 @@ NuttX EABI "buildroot" Toolchain details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. + NOTE: Unfortunately, the 4.6.3 EABI toolchain is not compatible with the + the NXFLAT tools. See the top-level TODO file (under "Binary loaders") for + more information about this problem. If you plan to use NXFLAT, please do not + use the GCC 4.6.3 EABI toochain; instead use the GCC 4.3.3 OABI toolchain. + See instructions below. + NuttX OABI "buildroot" Toolchain ================================ diff --git a/nuttx/configs/lpcxpresso-lpc1768/README.txt b/nuttx/configs/lpcxpresso-lpc1768/README.txt index cbc5f50e8..8ea038514 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/README.txt +++ b/nuttx/configs/lpcxpresso-lpc1768/README.txt @@ -445,6 +445,12 @@ NuttX EABI "buildroot" Toolchain details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. + NOTE: Unfortunately, the 4.6.3 EABI toolchain is not compatible with the + the NXFLAT tools. See the top-level TODO file (under "Binary loaders") for + more information about this problem. If you plan to use NXFLAT, please do not + use the GCC 4.6.3 EABI toochain; instead use the GCC 4.3.3 OABI toolchain. + See instructions below. + NuttX OABI "buildroot" Toolchain ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ diff --git a/nuttx/configs/mbed/README.txt b/nuttx/configs/mbed/README.txt index df509a199..4b413560a 100644 --- a/nuttx/configs/mbed/README.txt +++ b/nuttx/configs/mbed/README.txt @@ -159,6 +159,12 @@ NuttX EABI "buildroot" Toolchain details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. + NOTE: Unfortunately, the 4.6.3 EABI toolchain is not compatible with the + the NXFLAT tools. See the top-level TODO file (under "Binary loaders") for + more information about this problem. If you plan to use NXFLAT, please do not + use the GCC 4.6.3 EABI toochain; instead use the GCC 4.3.3 OABI toolchain. + See instructions below. + NuttX OABI "buildroot" Toolchain ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ diff --git a/nuttx/configs/nucleus2g/README.txt b/nuttx/configs/nucleus2g/README.txt index 39ae370cc..86a8944ab 100644 --- a/nuttx/configs/nucleus2g/README.txt +++ b/nuttx/configs/nucleus2g/README.txt @@ -219,6 +219,12 @@ NuttX EABI "buildroot" Toolchain details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. + NOTE: Unfortunately, the 4.6.3 EABI toolchain is not compatible with the + the NXFLAT tools. See the top-level TODO file (under "Binary loaders") for + more information about this problem. If you plan to use NXFLAT, please do not + use the GCC 4.6.3 EABI toochain; instead use the GCC 4.3.3 OABI toolchain. + See instructions below. + NuttX OABI "buildroot" Toolchain ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ diff --git a/nuttx/configs/olimex-lpc1766stk/README.txt b/nuttx/configs/olimex-lpc1766stk/README.txt index dcea9d0b7..f53ed4647 100644 --- a/nuttx/configs/olimex-lpc1766stk/README.txt +++ b/nuttx/configs/olimex-lpc1766stk/README.txt @@ -307,6 +307,12 @@ NuttX EABI "buildroot" Toolchain details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. + NOTE: Unfortunately, the 4.6.3 EABI toolchain is not compatible with the + the NXFLAT tools. See the top-level TODO file (under "Binary loaders") for + more information about this problem. If you plan to use NXFLAT, please do not + use the GCC 4.6.3 EABI toochain; instead use the GCC 4.3.3 OABI toolchain. + See instructions below. + NuttX OABI "buildroot" Toolchain ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ diff --git a/nuttx/configs/sam3u-ek/README.txt b/nuttx/configs/sam3u-ek/README.txt index 91f882409..fa5d52b69 100644 --- a/nuttx/configs/sam3u-ek/README.txt +++ b/nuttx/configs/sam3u-ek/README.txt @@ -162,6 +162,12 @@ NuttX EABI "buildroot" Toolchain details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. + NOTE: Unfortunately, the 4.6.3 EABI toolchain is not compatible with the + the NXFLAT tools. See the top-level TODO file (under "Binary loaders") for + more information about this problem. If you plan to use NXFLAT, please do not + use the GCC 4.6.3 EABI toochain; instead use the GCC 4.3.3 OABI toolchain. + See instructions below. + NuttX OABI "buildroot" Toolchain ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ diff --git a/nuttx/configs/shenzhou/README.txt b/nuttx/configs/shenzhou/README.txt index ff4cf7450..772c59a17 100644 --- a/nuttx/configs/shenzhou/README.txt +++ b/nuttx/configs/shenzhou/README.txt @@ -384,6 +384,12 @@ NuttX EABI buildroot Toolchain detailed PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. + NOTE: Unfortunately, the 4.6.3 EABI toolchain is not compatible with the + the NXFLAT tools. See the top-level TODO file (under "Binary loaders") for + more information about this problem. If you plan to use NXFLAT, please do not + use the GCC 4.6.3 EABI toochain; instead use the GCC 4.3.3 OABI toolchain. + See instructions below. + NuttX OABI "buildroot" Toolchain ================================ diff --git a/nuttx/configs/stm3210e-eval/README.txt b/nuttx/configs/stm3210e-eval/README.txt index 65f511320..50e413b42 100644 --- a/nuttx/configs/stm3210e-eval/README.txt +++ b/nuttx/configs/stm3210e-eval/README.txt @@ -170,6 +170,12 @@ NuttX EABI "buildroot" Toolchain details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. + NOTE: Unfortunately, the 4.6.3 EABI toolchain is not compatible with the + the NXFLAT tools. See the top-level TODO file (under "Binary loaders") for + more information about this problem. If you plan to use NXFLAT, please do not + use the GCC 4.6.3 EABI toochain; instead use the GCC 4.3.3 OABI toolchain. + See instructions below. + NuttX OABI "buildroot" Toolchain ================================ diff --git a/nuttx/configs/stm3220g-eval/README.txt b/nuttx/configs/stm3220g-eval/README.txt index 36fd75d25..58a6f156c 100644 --- a/nuttx/configs/stm3220g-eval/README.txt +++ b/nuttx/configs/stm3220g-eval/README.txt @@ -209,6 +209,12 @@ NuttX EABI "buildroot" Toolchain details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. + NOTE: Unfortunately, the 4.6.3 EABI toolchain is not compatible with the + the NXFLAT tools. See the top-level TODO file (under "Binary loaders") for + more information about this problem. If you plan to use NXFLAT, please do not + use the GCC 4.6.3 EABI toochain; instead use the GCC 4.3.3 OABI toolchain. + See instructions below. + NuttX OABI "buildroot" Toolchain ================================ diff --git a/nuttx/configs/stm3240g-eval/README.txt b/nuttx/configs/stm3240g-eval/README.txt index 6da18b7e5..8604f344a 100644 --- a/nuttx/configs/stm3240g-eval/README.txt +++ b/nuttx/configs/stm3240g-eval/README.txt @@ -216,6 +216,12 @@ NuttX EABI "buildroot" Toolchain details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. + NOTE: Unfortunately, the 4.6.3 EABI toolchain is not compatible with the + the NXFLAT tools. See the top-level TODO file (under "Binary loaders") for + more information about this problem. If you plan to use NXFLAT, please do not + use the GCC 4.6.3 EABI toochain; instead use the GCC 4.3.3 OABI toolchain. + See instructions below. + NuttX OABI "buildroot" Toolchain ================================ diff --git a/nuttx/configs/stm32f4discovery/README.txt b/nuttx/configs/stm32f4discovery/README.txt index 2054e90c6..dc25b220e 100644 --- a/nuttx/configs/stm32f4discovery/README.txt +++ b/nuttx/configs/stm32f4discovery/README.txt @@ -213,6 +213,12 @@ NuttX EABI "buildroot" Toolchain details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. + NOTE: Unfortunately, the 4.6.3 EABI toolchain is not compatible with the + the NXFLAT tools. See the top-level TODO file (under "Binary loaders") for + more information about this problem. If you plan to use NXFLAT, please do not + use the GCC 4.6.3 EABI toochain; instead use the GCC 4.3.3 OABI toolchain. + See instructions below. + NuttX OABI "buildroot" Toolchain ================================ diff --git a/nuttx/configs/twr-k60n512/README.txt b/nuttx/configs/twr-k60n512/README.txt index 27644deae..3b7b402d7 100644 --- a/nuttx/configs/twr-k60n512/README.txt +++ b/nuttx/configs/twr-k60n512/README.txt @@ -427,6 +427,12 @@ NuttX EABI "buildroot" Toolchain details PLUS some special instructions that you will need to follow if you are building a Cortex-M4 toolchain for Cygwin under Windows. + NOTE: Unfortunately, the 4.6.3 EABI toolchain is not compatible with the + the NXFLAT tools. See the top-level TODO file (under "Binary loaders") for + more information about this problem. If you plan to use NXFLAT, please do not + use the GCC 4.6.3 EABI toochain; instead use the GCC 4.3.3 OABI toolchain. + See instructions below. + NuttX OABI "buildroot" Toolchain ================================ diff --git a/nuttx/configs/vsn/README.txt b/nuttx/configs/vsn/README.txt index ae5f374dd..657cfdd89 100644 --- a/nuttx/configs/vsn/README.txt +++ b/nuttx/configs/vsn/README.txt @@ -167,6 +167,12 @@ NuttX EABI "buildroot" Toolchain details PLUS some special instructions that you will need to follow if you are building a Cortex-M3 toolchain for Cygwin under Windows. + NOTE: Unfortunately, the 4.6.3 EABI toolchain is not compatible with the + the NXFLAT tools. See the top-level TODO file (under "Binary loaders") for + more information about this problem. If you plan to use NXFLAT, please do not + use the GCC 4.6.3 EABI toochain; instead use the GCC 4.3.3 OABI toolchain. + See instructions below. + NuttX OABI "buildroot" Toolchain ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -- cgit v1.2.3 From e62b420882181f9dd656cd5598f6f8b86ada3fa8 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 11 Oct 2012 13:42:14 +0000 Subject: Another dtoa() fix from Mike Smith git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5229 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 1 + nuttx/configs/eagle100/README.txt | 13 +++- nuttx/configs/eagle100/nxflat/Make.defs | 78 +++++++++++------------ nuttx/configs/eagle100/thttpd/Make.defs | 78 +++++++++++------------ nuttx/configs/lpcxpresso-lpc1768/README.txt | 4 ++ nuttx/configs/lpcxpresso-lpc1768/thttpd/Make.defs | 14 ++-- nuttx/configs/olimex-lpc1766stk/README.txt | 4 ++ nuttx/configs/olimex-lpc1766stk/thttpd/Make.defs | 12 ++-- nuttx/lib/stdio/lib_libdtoa.c | 11 +++- 9 files changed, 121 insertions(+), 94 deletions(-) (limited to 'nuttx') diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 7121c506f..a8e045616 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3469,4 +3469,5 @@ xxx-nuttx-elf- vs. xxx-elf- * configs/shenzhou/*/Make.defs: Now uses the new buildroot 4.6.3 EABI toolchain. + * lib/stdio/lib_libdtoa.c: Another dtoa() fix from Mike Smith. diff --git a/nuttx/configs/eagle100/README.txt b/nuttx/configs/eagle100/README.txt index d868817cc..c9253960a 100644 --- a/nuttx/configs/eagle100/README.txt +++ b/nuttx/configs/eagle100/README.txt @@ -416,13 +416,24 @@ Where is one of the following: interface should also be functional, but is not enabled in this configuration). + nxflat: + This builds the NXFLAT example at apps/examples/nxfalt. + + NOTE: See note above with regard to the EABI/OABI buildroot + toolchains. This example can only be built using the older + OABI toolchain. + ostest: This configuration directory, performs a simple OS test using examples/ostest. thttpd: This builds the THTTPD web server example using the THTTPD and - the examples/thttpd application. + the apps/examples/thttpd application. + + NOTE: See note above with regard to the EABI/OABI buildroot + toolchains. This example can only be built using the older + OABI toolchain. By default, all of these examples are built to be used with the Luminary Ethernet Bootloader (you can change the ld.script file in any of these diff --git a/nuttx/configs/eagle100/nxflat/Make.defs b/nuttx/configs/eagle100/nxflat/Make.defs index 41e738ec8..780e85850 100644 --- a/nuttx/configs/eagle100/nxflat/Make.defs +++ b/nuttx/configs/eagle100/nxflat/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # configs/eagle100/nxflat/Make.defs # -# Copyright (C) 2009 Gregory Nutt. All rights reserved. +# Copyright (C) 2009, 2012 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -40,36 +40,36 @@ include ${TOPDIR}/tools/Config.mk # make -- Will build for the devkitARM toolchain # make CROSSDEV=arm-eabi- -- Will build for the devkitARM toolchain # make CROSSDEV=arm-none-eabi- -- Will build for the CodeSourcery toolchain -# make CROSSDEV=arm-nuttx-elf- -- Will build for the NuttX buildroot toolchain +# make CROSSDEV=arm-nuttx-elf- -- Will build for the NuttX OABI buildroot toolchain -CROSSDEV = arm-eabi- -CC = $(CROSSDEV)gcc -CXX = $(CROSSDEV)g++ -CPP = $(CROSSDEV)gcc -E -LD = $(CROSSDEV)ld -AR = $(CROSSDEV)ar rcs -NM = $(CROSSDEV)nm -OBJCOPY = $(CROSSDEV)objcopy -OBJDUMP = $(CROSSDEV)objdump +CROSSDEV = arm-eabi- +CC = $(CROSSDEV)gcc +CXX = $(CROSSDEV)g++ +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(CROSSDEV)ar rcs +NM = $(CROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +OBJDUMP = $(CROSSDEV)objdump -MKNXFLAT = mknxflat -LDNXFLAT = ldnxflat +MKNXFLAT = mknxflat +LDNXFLAT = ldnxflat ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} -ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} +ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} ifeq ($(CROSSDEV),arm-nuttx-elf-) - MKDEP = $(TOPDIR)/tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mkdeps.sh ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft ARCHINCLUDES = -I. -isystem $(TOPDIR)/include ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nxflat/ld.script MAXOPTIMIZATION = -Os else - WINTOOL = y - DIRLINK = $(TOPDIR)/tools/winlink.sh - DIRUNLINK = $(TOPDIR)/tools/unlink.sh - MKDEP = $(TOPDIR)/tools/mknulldeps.sh + WINTOOL = y + DIRLINK = $(TOPDIR)/tools/winlink.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}" @@ -83,42 +83,42 @@ else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer endif -ARCHCFLAGS = -fno-builtin +ARCHCFLAGS = -fno-builtin ARCHCXXFLAGS = -fno-builtin -fno-exceptions ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow ARCHWARNINGSXX = -Wall -Wshadow -ARCHDEFINES = +ARCHDEFINES = ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10 -CFLAGS = $(ARCHCFLAGS) $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ - $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS) -CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) \ - $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) -CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -AFLAGS = $(CFLAGS) -D__ASSEMBLY__ +CFLAGS = $(ARCHCFLAGS) $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ + $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS) +CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) \ + $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) +CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld \ - -no-check-sections + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoffset.ld \ + -no-check-sections LDNXFLATFLAGS = -e main -s 2048 -OBJEXT = .o -LIBEXT = .a -EXEEXT = +OBJEXT = .o +LIBEXT = .a +EXEEXT = ifneq ($(CROSSDEV),arm-nuttx-elf-) - LDFLAGS += -nostartfiles -nodefaultlibs + LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) - LDFLAGS += -g + LDFLAGS += -g endif -HOSTCC = gcc +HOSTCC = gcc HOSTINCLUDES = -I. -HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe -HOSTLDFLAGS = +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe +HOSTLDFLAGS = diff --git a/nuttx/configs/eagle100/thttpd/Make.defs b/nuttx/configs/eagle100/thttpd/Make.defs index 92f68d9f1..87157525b 100644 --- a/nuttx/configs/eagle100/thttpd/Make.defs +++ b/nuttx/configs/eagle100/thttpd/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # configs/eagle100/thttpd/Make.defs # -# Copyright (C) 2009 Gregory Nutt. All rights reserved. +# Copyright (C) 2009, 2012 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -40,36 +40,36 @@ include ${TOPDIR}/tools/Config.mk # make -- Will build for the devkitARM toolchain # make CROSSDEV=arm-eabi- -- Will build for the devkitARM toolchain # make CROSSDEV=arm-none-eabi- -- Will build for the CodeSourcery toolchain -# make CROSSDEV=arm-nuttx-elf- -- Will build for the NuttX buildroot toolchain +# make CROSSDEV=arm-nuttx-elf- -- Will build for the NuttX OABI buildroot toolchain -CROSSDEV = arm-eabi- -CC = $(CROSSDEV)gcc -CXX = $(CROSSDEV)g++ -CPP = $(CROSSDEV)gcc -E -LD = $(CROSSDEV)ld -AR = $(CROSSDEV)ar rcs -NM = $(CROSSDEV)nm -OBJCOPY = $(CROSSDEV)objcopy -OBJDUMP = $(CROSSDEV)objdump +CROSSDEV = arm-eabi- +CC = $(CROSSDEV)gcc +CXX = $(CROSSDEV)g++ +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(CROSSDEV)ar rcs +NM = $(CROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +OBJDUMP = $(CROSSDEV)objdump -MKNXFLAT = mknxflat -LDNXFLAT = ldnxflat +MKNXFLAT = mknxflat +LDNXFLAT = ldnxflat ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} -ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} +ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} ifeq ($(CROSSDEV),arm-nuttx-elf-) - MKDEP = $(TOPDIR)/tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mkdeps.sh ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft ARCHINCLUDES = -I. -isystem $(TOPDIR)/include ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/thttpd/ld.script MAXOPTIMIZATION = -Os else - WINTOOL = y - DIRLINK = $(TOPDIR)/tools/winlink.sh - DIRUNLINK = $(TOPDIR)/tools/unlink.sh - MKDEP = $(TOPDIR)/tools/mknulldeps.sh + WINTOOL = y + DIRLINK = $(TOPDIR)/tools/winlink.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}" @@ -83,42 +83,42 @@ else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer endif -ARCHCFLAGS = -fno-builtin +ARCHCFLAGS = -fno-builtin ARCHCXXFLAGS = -fno-builtin -fno-exceptions ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow ARCHWARNINGSXX = -Wall -Wshadow -ARCHDEFINES = +ARCHDEFINES = ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10 -CFLAGS = $(ARCHCFLAGS) $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ - $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS) -CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) \ - $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) -CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -AFLAGS = $(CFLAGS) -D__ASSEMBLY__ +CFLAGS = $(ARCHCFLAGS) $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ + $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS) +CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) \ + $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) +CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) \ - -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld \ - -no-check-sections + -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld \ + -no-check-sections LDNXFLATFLAGS = -e main -s 2048 -OBJEXT = .o -LIBEXT = .a -EXEEXT = +OBJEXT = .o +LIBEXT = .a +EXEEXT = ifneq ($(CROSSDEV),arm-nuttx-elf-) - LDFLAGS += -nostartfiles -nodefaultlibs + LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) - LDFLAGS += -g + LDFLAGS += -g endif -HOSTCC = gcc +HOSTCC = gcc HOSTINCLUDES = -I. -HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe -HOSTLDFLAGS = +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe +HOSTLDFLAGS = diff --git a/nuttx/configs/lpcxpresso-lpc1768/README.txt b/nuttx/configs/lpcxpresso-lpc1768/README.txt index 8ea038514..9660e12fe 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/README.txt +++ b/nuttx/configs/lpcxpresso-lpc1768/README.txt @@ -800,6 +800,10 @@ Where is one of the following: NOTE: You will need to build the NXFLAT toolchain as described above in order to use this example. + See also note above with regard to the EABI/OABI buildroot + toolchains. This example can only be built using the older + OABI toolchain. + Jumpers: Nothing special. Use the default base board jumper settings. diff --git a/nuttx/configs/lpcxpresso-lpc1768/thttpd/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/thttpd/Make.defs index b6a324546..0f3212522 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/thttpd/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/thttpd/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # configs/lpcxpresso-lpc1768/thttpd/Make.defs # -# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -59,11 +59,11 @@ endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin # OABI - # CROSSDEV = arm-nuttx-elf- - # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + CROSSDEV = arm-nuttx-elf- + ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft # EABI - CROSSDEV = arm-nuttx-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + # CROSSDEV = arm-nuttx-eabi- + # ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif ifeq ($(CONFIG_LPC17_CODEREDW),y) @@ -88,14 +88,14 @@ ifeq ($(WINTOOL),y) ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}" ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/thttpd/ld.script}" MAXOPTIMIZATION = -O2 - NXFLATLDSCRIPT = -T "${shell cygpath -w $(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld}" + NXFLATLDSCRIPT = -T "${shell cygpath -w $(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld}" else # Linux/Cygwin-native toolchain MKDEP = $(TOPDIR)/tools/mkdeps.sh ARCHINCLUDES = -I. -isystem $(TOPDIR)/include ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/thttpd/ld.script - NXFLATLDSCRIPT = -T"$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld" + NXFLATLDSCRIPT = -T"$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld" endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/olimex-lpc1766stk/README.txt b/nuttx/configs/olimex-lpc1766stk/README.txt index f53ed4647..b0b54f409 100644 --- a/nuttx/configs/olimex-lpc1766stk/README.txt +++ b/nuttx/configs/olimex-lpc1766stk/README.txt @@ -1025,6 +1025,10 @@ Where is one of the following: This builds the THTTPD web server example using the THTTPD and the apps/examples/thttpd application. + NOTE: See note above with regard to the EABI/OABI buildroot + toolchains. This example can only be built using the older + OABI toolchain. + usbserial: This configuration directory exercises the USB serial class driver at apps/examples/usbserial. See apps/examples/README.txt for diff --git a/nuttx/configs/olimex-lpc1766stk/thttpd/Make.defs b/nuttx/configs/olimex-lpc1766stk/thttpd/Make.defs index 11e155ed8..39e5ed299 100644 --- a/nuttx/configs/olimex-lpc1766stk/thttpd/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/thttpd/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # configs/olimex-lpc1766stk/thttpd/Make.defs # -# Copyright (C) 2010 Gregory Nutt. All rights reserved. +# Copyright (C) 2010, 2012 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -59,11 +59,11 @@ endif ifeq ($(CONFIG_LPC17_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin # OABI - # CROSSDEV = arm-nuttx-elf- - # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft + CROSSDEV = arm-nuttx-elf- + ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft # EABI - CROSSDEV = arm-nuttx-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + # CROSSDEV = arm-nuttx-eabi- + # ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -Os endif @@ -120,7 +120,7 @@ CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) AFLAGS = $(CFLAGS) -D__ASSEMBLY__ NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o diff --git a/nuttx/lib/stdio/lib_libdtoa.c b/nuttx/lib/stdio/lib_libdtoa.c index 1e022a8eb..667c49c53 100644 --- a/nuttx/lib/stdio/lib_libdtoa.c +++ b/nuttx/lib/stdio/lib_libdtoa.c @@ -224,8 +224,15 @@ static void lib_dtoa(FAR struct lib_outstream_s *obj, int fmt, int prec, for (i = expt; i > 0; i--) { - obj->put(obj, *digits); - digits++; + if (*digits != '\0') + { + obj->put(obj, *digits); + digits++; + } + else + { + obj->put(obj, '0'); + } } /* Get the length of the fractional part */ -- cgit v1.2.3 From 8de1d1d182bed68c075f279541c32a7493aef0bc Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 12 Oct 2012 15:38:42 +0000 Subject: Update Olimex-LPC1766STK setenv.sh to make it faster to use CodeSourcery. git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5230 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ReleaseNotes | 4 +++ nuttx/configs/olimex-lpc1766stk/README.txt | 2 +- nuttx/configs/olimex-lpc1766stk/ftpc/setenv.sh | 41 +++++++++++++++++++--- nuttx/configs/olimex-lpc1766stk/hidkbd/setenv.sh | 41 +++++++++++++++++++--- nuttx/configs/olimex-lpc1766stk/nettest/setenv.sh | 41 +++++++++++++++++++--- nuttx/configs/olimex-lpc1766stk/nsh/defconfig | 1 + nuttx/configs/olimex-lpc1766stk/nsh/setenv.sh | 41 +++++++++++++++++++--- nuttx/configs/olimex-lpc1766stk/nx/setenv.sh | 41 +++++++++++++++++++--- nuttx/configs/olimex-lpc1766stk/ostest/setenv.sh | 41 +++++++++++++++++++--- .../configs/olimex-lpc1766stk/slip-httpd/setenv.sh | 41 +++++++++++++++++++--- nuttx/configs/olimex-lpc1766stk/thttpd/setenv.sh | 41 +++++++++++++++++++--- .../configs/olimex-lpc1766stk/usbserial/setenv.sh | 41 +++++++++++++++++++--- .../configs/olimex-lpc1766stk/usbstorage/setenv.sh | 41 +++++++++++++++++++--- nuttx/configs/olimex-lpc1766stk/wlan/setenv.sh | 41 +++++++++++++++++++--- 14 files changed, 402 insertions(+), 56 deletions(-) (limited to 'nuttx') diff --git a/nuttx/ReleaseNotes b/nuttx/ReleaseNotes index 80362f5dd..b1d5f6064 100644 --- a/nuttx/ReleaseNotes +++ b/nuttx/ReleaseNotes @@ -1606,6 +1606,8 @@ The 61st release of NuttX, NuttX-5.14, was made on November 27, 2010. This release includes multiple, important bugfixes as well as a new driver for the NXP LPC1766. +This release corresponds with SVN release number: r3137 + Important bugfixes include: * Cortex-M3 Hard Fault. Fixed a hard fault problem that can occur @@ -2052,6 +2054,8 @@ interest expressed by members of the forum and because of the availability of newer, larger capacity AVR parts (that I don't have yet). +This release corresponds with SVN release number: r3730 + This release includes support for the following AVR boards. As with any initial support for new architectures, there are some incomplete areas and a few caveats that need to be stated. Here diff --git a/nuttx/configs/olimex-lpc1766stk/README.txt b/nuttx/configs/olimex-lpc1766stk/README.txt index b0b54f409..f638ed4ff 100644 --- a/nuttx/configs/olimex-lpc1766stk/README.txt +++ b/nuttx/configs/olimex-lpc1766stk/README.txt @@ -605,7 +605,7 @@ Using OpenOCD and GDB with an FT2232 JTAG emulator NOTES: 1. Loading the symbol-file is only useful if you have built NuttX to - inclulde debug symbols (by setting CONFIG_DEBUG_SYMBOLS=y in the + include debug symbols (by setting CONFIG_DEBUG_SYMBOLS=y in the .config file). 2. I usually have to reset, halt, and 'load nuttx' a second time. For some reason, the first time apparently does not fully program the diff --git a/nuttx/configs/olimex-lpc1766stk/ftpc/setenv.sh b/nuttx/configs/olimex-lpc1766stk/ftpc/setenv.sh index df1091690..f9194c00d 100755 --- a/nuttx/configs/olimex-lpc1766stk/ftpc/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/ftpc/setenv.sh @@ -32,16 +32,47 @@ # POSSIBILITY OF SUCH DAMAGE. # -if [ "$(basename $0)" = "setenv.sh" ] ; then +if [ "$_" = "$0" ] ; then echo "You must source this script, not run it!" 1>&2 exit 1 fi -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi - WD=`pwd` +if [ ! -x "setenv.sh" ]; then + echo "This script must be executed from the top-level NuttX build directory" + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then + export PATH_ORIG="${PATH}" +fi + +# This is the Cygwin path to the location where I installed the RIDE +# toolchain under windows. You will also have to edit this if you install +# the RIDE toolchain in any other location +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" + +# This is the Cygwin path to the location where I installed the CodeSourcery +# toolchain under windows. You will also have to edit this if you install +# the CodeSourcery toolchain in any other location +# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" + +# These are the Cygwin paths to the locations where I installed the Atollic +# toolchain under windows. You will also have to edit this if you install +# the Atollic toolchain in any other location. /usr/bin is added before +# the Atollic bin path because there is are binaries named gcc.exe and g++.exe +# at those locations as well. +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/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" + +# The Olimex-lpc1766stk/tools directory export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools" -export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" -export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" + +# Add the path to the toolchain and tools directory to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/olimex-lpc1766stk/hidkbd/setenv.sh b/nuttx/configs/olimex-lpc1766stk/hidkbd/setenv.sh index e4e130c24..4c76646f9 100755 --- a/nuttx/configs/olimex-lpc1766stk/hidkbd/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/hidkbd/setenv.sh @@ -32,16 +32,47 @@ # POSSIBILITY OF SUCH DAMAGE. # -if [ "$(basename $0)" = "setenv.sh" ] ; then +if [ "$_" = "$0" ] ; then echo "You must source this script, not run it!" 1>&2 exit 1 fi -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi - WD=`pwd` +if [ ! -x "setenv.sh" ]; then + echo "This script must be executed from the top-level NuttX build directory" + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then + export PATH_ORIG="${PATH}" +fi + +# This is the Cygwin path to the location where I installed the RIDE +# toolchain under windows. You will also have to edit this if you install +# the RIDE toolchain in any other location +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" + +# This is the Cygwin path to the location where I installed the CodeSourcery +# toolchain under windows. You will also have to edit this if you install +# the CodeSourcery toolchain in any other location +# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" + +# These are the Cygwin paths to the locations where I installed the Atollic +# toolchain under windows. You will also have to edit this if you install +# the Atollic toolchain in any other location. /usr/bin is added before +# the Atollic bin path because there is are binaries named gcc.exe and g++.exe +# at those locations as well. +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/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" + +# The Olimex-lpc1766stk/tools directory export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools" -export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" -export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" + +# Add the path to the toolchain and tools directory to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/olimex-lpc1766stk/nettest/setenv.sh b/nuttx/configs/olimex-lpc1766stk/nettest/setenv.sh index 92c6bdf5e..d544f4470 100755 --- a/nuttx/configs/olimex-lpc1766stk/nettest/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/nettest/setenv.sh @@ -32,16 +32,47 @@ # POSSIBILITY OF SUCH DAMAGE. # -if [ "$(basename $0)" = "setenv.sh" ] ; then +if [ "$_" = "$0" ] ; then echo "You must source this script, not run it!" 1>&2 exit 1 fi -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi - WD=`pwd` +if [ ! -x "setenv.sh" ]; then + echo "This script must be executed from the top-level NuttX build directory" + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then + export PATH_ORIG="${PATH}" +fi + +# This is the Cygwin path to the location where I installed the RIDE +# toolchain under windows. You will also have to edit this if you install +# the RIDE toolchain in any other location +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" + +# This is the Cygwin path to the location where I installed the CodeSourcery +# toolchain under windows. You will also have to edit this if you install +# the CodeSourcery toolchain in any other location +# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" + +# These are the Cygwin paths to the locations where I installed the Atollic +# toolchain under windows. You will also have to edit this if you install +# the Atollic toolchain in any other location. /usr/bin is added before +# the Atollic bin path because there is are binaries named gcc.exe and g++.exe +# at those locations as well. +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/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" + +# The Olimex-lpc1766stk/tools directory export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools" -export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" -export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" + +# Add the path to the toolchain and tools directory to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/olimex-lpc1766stk/nsh/defconfig b/nuttx/configs/olimex-lpc1766stk/nsh/defconfig index c2722cb9b..d5333a9f3 100755 --- a/nuttx/configs/olimex-lpc1766stk/nsh/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/nsh/defconfig @@ -262,6 +262,7 @@ CONFIG_NFILE_DESCRIPTORS=8 CONFIG_NFILE_STREAMS=8 CONFIG_NAME_MAX=32 CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STDIO_LINEBUFFER=y CONFIG_NUNGET_CHARS=2 CONFIG_PREALLOC_MQ_MSGS=4 CONFIG_MQ_MAXMSGSIZE=32 diff --git a/nuttx/configs/olimex-lpc1766stk/nsh/setenv.sh b/nuttx/configs/olimex-lpc1766stk/nsh/setenv.sh index 089165f69..84150b068 100755 --- a/nuttx/configs/olimex-lpc1766stk/nsh/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/nsh/setenv.sh @@ -32,16 +32,47 @@ # POSSIBILITY OF SUCH DAMAGE. # -if [ "$(basename $0)" = "setenv.sh" ] ; then +if [ "$_" = "$0" ] ; then echo "You must source this script, not run it!" 1>&2 exit 1 fi -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi - WD=`pwd` +if [ ! -x "setenv.sh" ]; then + echo "This script must be executed from the top-level NuttX build directory" + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then + export PATH_ORIG="${PATH}" +fi + +# This is the Cygwin path to the location where I installed the RIDE +# toolchain under windows. You will also have to edit this if you install +# the RIDE toolchain in any other location +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" + +# This is the Cygwin path to the location where I installed the CodeSourcery +# toolchain under windows. You will also have to edit this if you install +# the CodeSourcery toolchain in any other location +# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" + +# These are the Cygwin paths to the locations where I installed the Atollic +# toolchain under windows. You will also have to edit this if you install +# the Atollic toolchain in any other location. /usr/bin is added before +# the Atollic bin path because there is are binaries named gcc.exe and g++.exe +# at those locations as well. +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/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" + +# The Olimex-lpc1766stk/tools directory export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools" -export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" -export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" + +# Add the path to the toolchain and tools directory to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/olimex-lpc1766stk/nx/setenv.sh b/nuttx/configs/olimex-lpc1766stk/nx/setenv.sh index 69cee3997..b94b47ad4 100755 --- a/nuttx/configs/olimex-lpc1766stk/nx/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/nx/setenv.sh @@ -32,16 +32,47 @@ # POSSIBILITY OF SUCH DAMAGE. # -if [ "$(basename $0)" = "setenv.sh" ] ; then +if [ "$_" = "$0" ] ; then echo "You must source this script, not run it!" 1>&2 exit 1 fi -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi - WD=`pwd` +if [ ! -x "setenv.sh" ]; then + echo "This script must be executed from the top-level NuttX build directory" + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then + export PATH_ORIG="${PATH}" +fi + +# This is the Cygwin path to the location where I installed the RIDE +# toolchain under windows. You will also have to edit this if you install +# the RIDE toolchain in any other location +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" + +# This is the Cygwin path to the location where I installed the CodeSourcery +# toolchain under windows. You will also have to edit this if you install +# the CodeSourcery toolchain in any other location +# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" + +# These are the Cygwin paths to the locations where I installed the Atollic +# toolchain under windows. You will also have to edit this if you install +# the Atollic toolchain in any other location. /usr/bin is added before +# the Atollic bin path because there is are binaries named gcc.exe and g++.exe +# at those locations as well. +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/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" + +# The Olimex-lpc1766stk/tools directory export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools" -export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" -export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" + +# Add the path to the toolchain and tools directory to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/olimex-lpc1766stk/ostest/setenv.sh b/nuttx/configs/olimex-lpc1766stk/ostest/setenv.sh index b61805da0..a5547b3bf 100755 --- a/nuttx/configs/olimex-lpc1766stk/ostest/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/ostest/setenv.sh @@ -32,16 +32,47 @@ # POSSIBILITY OF SUCH DAMAGE. # -if [ "$(basename $0)" = "setenv.sh" ] ; then +if [ "$_" = "$0" ] ; then echo "You must source this script, not run it!" 1>&2 exit 1 fi -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi - WD=`pwd` +if [ ! -x "setenv.sh" ]; then + echo "This script must be executed from the top-level NuttX build directory" + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then + export PATH_ORIG="${PATH}" +fi + +# This is the Cygwin path to the location where I installed the RIDE +# toolchain under windows. You will also have to edit this if you install +# the RIDE toolchain in any other location +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" + +# This is the Cygwin path to the location where I installed the CodeSourcery +# toolchain under windows. You will also have to edit this if you install +# the CodeSourcery toolchain in any other location +# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" + +# These are the Cygwin paths to the locations where I installed the Atollic +# toolchain under windows. You will also have to edit this if you install +# the Atollic toolchain in any other location. /usr/bin is added before +# the Atollic bin path because there is are binaries named gcc.exe and g++.exe +# at those locations as well. +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/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" + +# The Olimex-lpc1766stk/tools directory export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools" -export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" -export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" + +# Add the path to the toolchain and tools directory to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/olimex-lpc1766stk/slip-httpd/setenv.sh b/nuttx/configs/olimex-lpc1766stk/slip-httpd/setenv.sh index 50364e4a1..35dbd55b3 100755 --- a/nuttx/configs/olimex-lpc1766stk/slip-httpd/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/slip-httpd/setenv.sh @@ -32,16 +32,47 @@ # POSSIBILITY OF SUCH DAMAGE. # -if [ "$(basename $0)" = "setenv.sh" ] ; then +if [ "$_" = "$0" ] ; then echo "You must source this script, not run it!" 1>&2 exit 1 fi -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi - WD=`pwd` +if [ ! -x "setenv.sh" ]; then + echo "This script must be executed from the top-level NuttX build directory" + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then + export PATH_ORIG="${PATH}" +fi + +# This is the Cygwin path to the location where I installed the RIDE +# toolchain under windows. You will also have to edit this if you install +# the RIDE toolchain in any other location +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" + +# This is the Cygwin path to the location where I installed the CodeSourcery +# toolchain under windows. You will also have to edit this if you install +# the CodeSourcery toolchain in any other location +# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" + +# These are the Cygwin paths to the locations where I installed the Atollic +# toolchain under windows. You will also have to edit this if you install +# the Atollic toolchain in any other location. /usr/bin is added before +# the Atollic bin path because there is are binaries named gcc.exe and g++.exe +# at those locations as well. +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/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" + +# The Olimex-lpc1766stk/tools directory export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools" -export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" -export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" + +# Add the path to the toolchain and tools directory to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/olimex-lpc1766stk/thttpd/setenv.sh b/nuttx/configs/olimex-lpc1766stk/thttpd/setenv.sh index 2a9ddae15..bcf0c4dea 100755 --- a/nuttx/configs/olimex-lpc1766stk/thttpd/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/thttpd/setenv.sh @@ -32,16 +32,47 @@ # POSSIBILITY OF SUCH DAMAGE. # -if [ "$(basename $0)" = "setenv.sh" ] ; then +if [ "$_" = "$0" ] ; then echo "You must source this script, not run it!" 1>&2 exit 1 fi -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi - WD=`pwd` +if [ ! -x "setenv.sh" ]; then + echo "This script must be executed from the top-level NuttX build directory" + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then + export PATH_ORIG="${PATH}" +fi + +# This is the Cygwin path to the location where I installed the RIDE +# toolchain under windows. You will also have to edit this if you install +# the RIDE toolchain in any other location +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" + +# This is the Cygwin path to the location where I installed the CodeSourcery +# toolchain under windows. You will also have to edit this if you install +# the CodeSourcery toolchain in any other location +# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" + +# These are the Cygwin paths to the locations where I installed the Atollic +# toolchain under windows. You will also have to edit this if you install +# the Atollic toolchain in any other location. /usr/bin is added before +# the Atollic bin path because there is are binaries named gcc.exe and g++.exe +# at those locations as well. +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/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" + +# The Olimex-lpc1766stk/tools directory export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools" -export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" -export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" + +# Add the path to the toolchain and tools directory to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/olimex-lpc1766stk/usbserial/setenv.sh b/nuttx/configs/olimex-lpc1766stk/usbserial/setenv.sh index b12d65852..ea9fe6c67 100755 --- a/nuttx/configs/olimex-lpc1766stk/usbserial/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/usbserial/setenv.sh @@ -32,16 +32,47 @@ # POSSIBILITY OF SUCH DAMAGE. # -if [ "$(basename $0)" = "setenv.sh" ] ; then +if [ "$_" = "$0" ] ; then echo "You must source this script, not run it!" 1>&2 exit 1 fi -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi - WD=`pwd` +if [ ! -x "setenv.sh" ]; then + echo "This script must be executed from the top-level NuttX build directory" + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then + export PATH_ORIG="${PATH}" +fi + +# This is the Cygwin path to the location where I installed the RIDE +# toolchain under windows. You will also have to edit this if you install +# the RIDE toolchain in any other location +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" + +# This is the Cygwin path to the location where I installed the CodeSourcery +# toolchain under windows. You will also have to edit this if you install +# the CodeSourcery toolchain in any other location +# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" + +# These are the Cygwin paths to the locations where I installed the Atollic +# toolchain under windows. You will also have to edit this if you install +# the Atollic toolchain in any other location. /usr/bin is added before +# the Atollic bin path because there is are binaries named gcc.exe and g++.exe +# at those locations as well. +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/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" + +# The Olimex-lpc1766stk/tools directory export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools" -export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" -export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" + +# Add the path to the toolchain and tools directory to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/olimex-lpc1766stk/usbstorage/setenv.sh b/nuttx/configs/olimex-lpc1766stk/usbstorage/setenv.sh index 58fd5d04d..fa23269fb 100755 --- a/nuttx/configs/olimex-lpc1766stk/usbstorage/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/usbstorage/setenv.sh @@ -32,16 +32,47 @@ # POSSIBILITY OF SUCH DAMAGE. # -if [ "$(basename $0)" = "setenv.sh" ] ; then +if [ "$_" = "$0" ] ; then echo "You must source this script, not run it!" 1>&2 exit 1 fi -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi - WD=`pwd` +if [ ! -x "setenv.sh" ]; then + echo "This script must be executed from the top-level NuttX build directory" + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then + export PATH_ORIG="${PATH}" +fi + +# This is the Cygwin path to the location where I installed the RIDE +# toolchain under windows. You will also have to edit this if you install +# the RIDE toolchain in any other location +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" + +# This is the Cygwin path to the location where I installed the CodeSourcery +# toolchain under windows. You will also have to edit this if you install +# the CodeSourcery toolchain in any other location +# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" + +# These are the Cygwin paths to the locations where I installed the Atollic +# toolchain under windows. You will also have to edit this if you install +# the Atollic toolchain in any other location. /usr/bin is added before +# the Atollic bin path because there is are binaries named gcc.exe and g++.exe +# at those locations as well. +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/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" + +# The Olimex-lpc1766stk/tools directory export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools" -export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" -export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" + +# Add the path to the toolchain and tools directory to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/olimex-lpc1766stk/wlan/setenv.sh b/nuttx/configs/olimex-lpc1766stk/wlan/setenv.sh index 6e6c79ab2..b7ada2bc2 100755 --- a/nuttx/configs/olimex-lpc1766stk/wlan/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/wlan/setenv.sh @@ -32,16 +32,47 @@ # POSSIBILITY OF SUCH DAMAGE. # -if [ "$(basename $0)" = "setenv.sh" ] ; then +if [ "$_" = "$0" ] ; then echo "You must source this script, not run it!" 1>&2 exit 1 fi -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi - WD=`pwd` +if [ ! -x "setenv.sh" ]; then + echo "This script must be executed from the top-level NuttX build directory" + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then + export PATH_ORIG="${PATH}" +fi + +# This is the Cygwin path to the location where I installed the RIDE +# toolchain under windows. You will also have to edit this if you install +# the RIDE toolchain in any other location +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" + +# This is the Cygwin path to the location where I installed the CodeSourcery +# toolchain under windows. You will also have to edit this if you install +# the CodeSourcery toolchain in any other location +# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" + +# These are the Cygwin paths to the locations where I installed the Atollic +# toolchain under windows. You will also have to edit this if you install +# the Atollic toolchain in any other location. /usr/bin is added before +# the Atollic bin path because there is are binaries named gcc.exe and g++.exe +# at those locations as well. +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/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" + +# The Olimex-lpc1766stk/tools directory export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools" -export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" -export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" + +# Add the path to the toolchain and tools directory to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" -- cgit v1.2.3